目录

  • 前言
    • 系统版本
  • 一、使用realsense SDK录制bag包的情况
    • 1.录制视频
    • 2.、提取rgb和depth图片
      • 1.
      • 2.
    • 3.对齐时间戳
  • 二、用realsense-ros打开相机录制bag包
    • 1.将深度图对齐到RGB
    • 2.使用realsense-ros打开相机
    • 3.录制rosbag
      • 1.直接使用命令
      • 2.写一个launch文件
    • 4.提取图像以及对齐时间戳

前言

本文写于2023年3月14日。D435i相机的rgb图像与depth图像的像素没有对齐,在此记录一下如何像素对齐

系统版本

Ubuntu18.04 + ROS melodic

一、使用realsense SDK录制bag包的情况

1.录制视频

这一步需要使用InterRealSenseD435i SDK2,可以参考此链接安装。
打开Intel RealSense Viewer。设置Depth Stream以及Color Stream的图像分辨率为640 × 480,设置采集帧率为30 fps。点击左上角的Record按钮即可进行录制,开始录制后,点击左上角的Stop按钮即可结束录制并保存录制结果。

若点击Record按钮后出现以下报错,则更改一下保存路径。

UNKNOWN in rs2_create_record_device_ex(device:0x7f151c000b20, file:/):
Error opening file: /home/d/Documents/20220723_223742.bag


点击右上角的齿轮图标,选择Settings,然后改变存储路径,之后点击ApplyOK

结束录制后,在相应存储路径下即生成.bag文件。

2.、提取rgb和depth图片

1.

首先,进入bag文件的存储路径并打开终端,通过rosbag info 20220723_202328.bag查看待提取的深度图及彩色图所对应的 topic,如下图所示:


新建文件夹room(此名称随意),在此文件夹下新建文件夹rgbdepth保存提取出来的深度图和彩色图,同时新建文件rgb.txtdepth.txt为对齐时间戳做准备。

2.

执行以下python脚本对齐并提取图像.py
:我保存的路径出现了中文,所以在第一行加入了# -*- coding: utf-8 -*-,否则会报错SyntaxError: Non-ASCII character '\xe8' in file 参考链接

这部分在原有的提取图片的基础上添加了像素对齐的功能
参考链接:
Realsense相机在linux下的配置使用,RGB与depth图像对齐(此博客有对齐图像与非对齐图像的比较)
realsense深度图像读取对齐与保存(下面程序的框架来源)
realsense bag文件时间戳获取(下面程序时间戳获取来源)

#coding=utf-8
import pyrealsense2 as rs
import numpy as np
import cv2
import time
import os
#像素对齐了
pipeline = rs.pipeline()#Create a config并配置要流​​式传输的管道
config = rs.config()
config.enable_device_from_file("/home/d/下载/20221128_161053.bag")#这是打开相机API录制的视频
# config.enable_stream(rs.stream.depth, 640, 480, rs.format.z16, 30)
# config.enable_stream(rs.stream.color, 640, 480, rs.format.bgr8, 30)profile = pipeline.start(config)depth_sensor = profile.get_device().first_depth_sensor()
depth_scale = depth_sensor.get_depth_scale()
print("Depth Scale is: " , depth_scale)align_to = rs.stream.color
align = rs.align(align_to)# 保存路径
save_path = '/home/d/文档/数据集/自己录的D435i/table/'# 保存的图片和实时的图片界面
# cv2.namedWindow("live", cv2.WINDOW_AUTOSIZE)
# cv2.namedWindow("save", cv2.WINDOW_AUTOSIZE)
number = 0file_handle1 = open('/home/d/文档/数据集/自己录的D435i/table/rgb.txt', 'w')
file_handle2 = open('/home/d/文档/数据集/自己录的D435i/table/depth.txt', 'w')# 主循环
try:while True:#获得深度图的时间戳frames = pipeline.wait_for_frames()number = number + 1depth_timestamp = "%.6f" % (frames.timestamp / 1000)rgb_timestamp = "%.6f" % (frames.timestamp / 1000 + 0.000017)#对比了 提取图片.py 的时间戳,发现rgb比depth多0.000017aligned_frames = align.process(frames)#获取对齐后的深度图与彩色图aligned_depth_frame = aligned_frames.get_depth_frame()color_frame = aligned_frames.get_color_frame()if not aligned_depth_frame or not color_frame:continuedepth_data = np.asanyarray(aligned_depth_frame.get_data(), dtype="float16")depth_image = np.asanyarray(aligned_depth_frame.get_data())color_image = np.asanyarray(color_frame.get_data())color_image = cv2.cvtColor(color_image,cv2.COLOR_BGR2RGB)depth_mapped_image = cv2.applyColorMap(cv2.convertScaleAbs(depth_image, alpha=0.05), cv2.COLORMAP_JET)#下面两行是opencv显示部分# cv2.imshow("live", np.hstack((color_image, depth_mapped_image)))# key = cv2.waitKey(30)rgb_image_name = rgb_timestamp+ ".png"depth_image_name = depth_timestamp+ ".png"rgb_path = "rgb/" + rgb_image_namedepth_path = "depth/" + depth_image_name# rgb图片路径及图片保存为png格式file_handle1.write(rgb_timestamp + " " + rgb_path + '\n')cv2.imwrite(save_path + rgb_path, color_image)# depth图片路径及图片保存为png格式file_handle2.write(depth_timestamp + " " + depth_path + '\n')cv2.imwrite(save_path + depth_path, depth_image)print(number, rgb_timestamp, depth_timestamp)#cv2.imshow("save", np.hstack((saved_color_image, saved_depth_mapped_image)))#查看话题包有多少帧图片,下面就改成多少if number == 2890:cv2.destroyAllWindows()break
finally:pipeline.stop()file_handle1.close()
file_handle2.close()

需要将以下几行路径改成自己对应的路径

config.enable_device_from_file("/home/d/下载/20221128_161053.bag")save_path = '/home/d/文档/数据集/自己录的D435i/table/'file_handle1 = open('/home/d/文档/数据集/自己录的D435i/table/rgb.txt', 'w')
file_handle2 = open('/home/d/文档/数据集/自己录的D435i/table/depth.txt', 'w')

还有判断停止的条件

#查看话题包有多少帧图片,下面就改成多少
if number == 2890:

改好了之后打开终端输入以下指令执行python脚本

python 对齐并提取图像.py

3.对齐时间戳

由于深度图及彩色图的时间戳并非严格一一对齐,存在一定的时间差,因此需将深度图及彩色图按照时间戳最接近原则进行两两配对。将associate.py脚本文件存储至room文件夹下,如图所示:

associate.py脚本文件:

"""
The RealSense provides the color and depth images in an un-synchronized way. This means that the set of time stamps from the color images do not intersect with those of the depth images. Therefore, we need some way of associating color images to depth images.For this purpose, you can use the ''associate.py'' script. It reads the time stamps from the rgb.txt file and the depth.txt file, and joins them by finding the best matches.
"""import argparse
import sys
import os
import numpydef read_file_list(filename):"""Reads a trajectory from a text file.File format:The file format is "stamp d1 d2 d3 ...", where stamp denotes the time stamp (to be matched)and "d1 d2 d3.." is arbitary data (e.g., a 3D position and 3D orientation) associated to this timestamp.Input:filename -- File nameOutput:dict -- dictionary of (stamp,data) tuples"""file = open(filename)data = file.read()lines = data.replace(",", " ").replace("\t", " ").split("\n")list = [[v.strip() for v in line.split(" ") if v.strip() != ""] for line in lines iflen(line) > 0 and line[0] != "#"]list = [(float(l[0]), l[1:]) for l in list if len(l) > 1]return dict(list)def associate(first_list, second_list, offset, max_difference):"""Associate two dictionaries of (stamp,data). As the time stamps never match exactly, we aimto find the closest match for every input tuple.Input:first_list -- first dictionary of (stamp,data) tuplessecond_list -- second dictionary of (stamp,data) tuplesoffset -- time offset between both dictionaries (e.g., to model the delay between the sensors)max_difference -- search radius for candidate generationOutput:matches -- list of matched tuples ((stamp1,data1),(stamp2,data2))"""first_keys = first_list.keys()second_keys = second_list.keys()potential_matches = [(abs(a - (b + offset)), a, b)for a in first_keysfor b in second_keysif abs(a - (b + offset)) < max_difference]potential_matches.sort()matches = []for diff, a, b in potential_matches:if a in first_keys and b in second_keys:first_keys.remove(a)second_keys.remove(b)matches.append((a, b))matches.sort()return matchesif __name__ == '__main__':# parse command lineparser = argparse.ArgumentParser(description='''This script takes two data files with timestamps and associates them   ''')parser.add_argument('first_file', help='first text file (format: timestamp data)')parser.add_argument('second_file', help='second text file (format: timestamp data)')parser.add_argument('--first_only', help='only output associated lines from first file', action='store_true')parser.add_argument('--offset', help='time offset added to the timestamps of the second file (default: 0.0)',default=0.0)parser.add_argument('--max_difference',help='maximally allowed time difference for matching entries (default: 0.02)', default=0.02)args = parser.parse_args()first_list = read_file_list(args.first_file)second_list = read_file_list(args.second_file)matches = associate(first_list, second_list, float(args.offset), float(args.max_difference))if args.first_only:for a, b in matches:print("%f %s" % (a, " ".join(first_list[a])))else:for a, b in matches:print("%f %s %f %s" % (a, " ".join(first_list[a]), b - float(args.offset), " ".join(second_list[b])))

在该路径下打开终端并通过执行如下命令生成配对结果associate.txt

python associate.py rgb.txt depth.txt > associate.txt

至此,数据集制作完成。

二、用realsense-ros打开相机录制bag包

1.将深度图对齐到RGB

打开realsense-ros/realsense2_camera/launch/rs_d435_camera_with_model.launch文件,将align_depth的值改为true

2.使用realsense-ros打开相机

切换到安装realsense-ros的工作空间

source devel/setup.bash
roslaunch realsense2_camera rs_d435_camera_with_model.launch

之后新建终端查看rostopic list/camera/aligned_depth_to_color/image_raw就是对齐后的深度图像话题

3.录制rosbag

参考链接:如何优雅的录制ROS的rosbag包?

1.直接使用命令

rosbag record -O xxx.bag topic-name

根据上面的格式,我把路径补全,并且选择监听的话题,因此我使用下面的命令

rosbag record -O /home/d/1.bag /camera/color/image_raw /camera/aligned_depth_to_color/image_raw

录制结束按Ctrl+C暂停

2.写一个launch文件

<launch><node pkg="rosbag" type="record" name="bag_record" args="topic-name1 topic-name1 -O xxxx"/>
</launch>

根据上面的格式,我把路径补全,并且选择监听的话题,因此我launch文件改成下面的

<launch><node pkg="rosbag" type="record" name="bag_record" args="/camera/color/image_raw /camera/aligned_depth_to_color/image_raw -O /home/d/1"/>
</launch>

我把上面的文件命名为rosbag_record.launch,并且放在/home/d/catkin_ws/src/realsense-ros/realsense2_camera/launch/路径下
切换到安装realsense-ros的工作空间

source devel/setup.bash
roslaunch realsense2_camera rosbag_record.launch

录制结束按Ctrl+C暂停

4.提取图像以及对齐时间戳

新建文件夹room(此名称随意),在此文件夹下新建文件夹rgbdepth保存提取出来的深度图和彩色图,同时新建文件rgb.txtdepth.txt为对齐时间戳做准备
执行以下python脚本提取图像.py

注意:该脚本只能提取图像,并不能对齐像素(因为第二部分的第1步已经对齐过了)

# -*- coding: utf-8 -*-import roslib
import rosbag
import rospy
import cv2
import os
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
from cv_bridge import CvBridgeErrorrgb = '/home/d/视频/room/rgb/'  #rgb path
depth = '/home/d/视频/room/depth/'   #depth path
bridge = CvBridge()file_handle1 = open('/home/d/视频/room/depth.txt', 'w')
file_handle2 = open('/home/d/视频/room/rgb.txt', 'w')with rosbag.Bag('/home/d/视频/20220723_202328.bag', 'r') as bag:for topic,msg,t in bag.read_messages():if topic == "/camera/aligned_depth_to_color/image_raw":  #depth topiccv_image = bridge.imgmsg_to_cv2(msg)timestr = "%.6f" %  msg.header.stamp.to_sec()   #depth time stampimage_name = timestr+ ".png"path = "depth/" + image_namefile_handle1.write(timestr + " " + path + '\n')cv2.imwrite(depth + image_name, cv_image)if topic == "/camera/color/image_raw":   #rgb topiccv_image = bridge.imgmsg_to_cv2(msg,"bgr8")timestr = "%.6f" %  msg.header.stamp.to_sec()   #rgb time stampimage_name = timestr+ ".png"path = "rgb/" + image_namefile_handle2.write(timestr + " " + path + '\n')cv2.imwrite(rgb + image_name, cv_image)
file_handle1.close()
file_handle2.close()

需要将以下几行路径改成自己对应的路径

rgb = '/home/d/视频/room/rgb/'  #rgb path
depth = '/home/d/视频/room/depth/'   #depth path
bridge = CvBridge()file_handle1 = open('/home/d/视频/room/depth.txt', 'w')
file_handle2 = open('/home/d/视频/room/rgb.txt', 'w')with rosbag.Bag('/home/d/视频/20220723_202328.bag', 'r') as bag:

改好了之后打开终端输入以下指令执行python脚本

python 提取图像.py

提取完了之后按照上面相同的方式对齐时间戳即可

使用D435i相机录制TUM格式的数据集相关推荐

  1. 使用小觅相机录制指定话题的数据集

    1 开启小觅相机(安装好相机的SDK,按照官网安装) make init make ros 注意,发现一个Bug 我的相机不能在ROS中启动,最终换了一个usb口,因为我的电脑如果有两个USB口,好像 ...

  2. 使用小觅相机录制数据集

    文章目录 1 目的 2 方法 2.1 SDK 2.2 ROS bag 2.2.1 录制bag 2.2.2 从bag文件中提取数据 2.2.2.1 提取图像 2.2.2.2 提取IMU数据 3 相关核心 ...

  3. 使用ZED相机录制事件双目数据集

    1 ZED双目相机windows下采集图像 如果使用的相机不同,请根据具体相机的SDK不同编写代码录制,这里我使用的ZED_2i相机.本身相机录制文件会保存成SVO格式,这里我使用opencv的imw ...

  4. Ubuntu 18.04 Intel RealSense D435i 相机标定教程

    1.D435i相机简介 RealSenseD435i 是一款立体视觉深度相机,如下图所示,其集成了两个红外传感器(IR Stereo Camera).一个红外激光发射器(IR Projector)和一 ...

  5. D435i相机的标定及VINS-Fusion config文件修改

    引言 当我们想使用D435i相机去跑VINS-Fusion时,如果不把标定过的相机信息写入config文件中就运行,这样运动轨迹会抖动十分严重,里程计很容易漂.接下来将介绍如何标定D435i相机,并设 ...

  6. T265/D435i相机和相机与IMU参数获取,也可以通过realsense-viewer直接获取

    T265/D435i相机和相机与IMU参数获取 参考这篇博文 https://blog.csdn.net/crp997576280/article/details/109544456 我想我们也需要理 ...

  7. ROS轨迹保存为tum格式,并用evo轨迹绘制

    安装evo evo共有两种安装方式 快捷安装 ,直接安装最新的稳定发行版: pip install evo --upgrade --no-binary evo 源码安装 ,下载源码进行安装:     ...

  8. Ubuntu20.04+ROSnoetic运行A-LOAM并保存TUM格式轨迹

    1.准备工作 需要提前安装Ceres solver和PCL,如果你安装的是完整版ROS那么PCL已经自动安装好了,ceres安装参见我另一篇博客https://blog.csdn.net/weixin ...

  9. D435i相机获取某一点深度图像的深度值(ROS实现以及官方API调用)

    文章目录 前言 一.ROS实现深度值的获取 代码解释 二.使用方法 三.调用官方API获取深度 总结 前言 最近这段时间一直在研究intel的D435i相机,主要用来实现识别物体并反馈物体的深度值.特 ...

最新文章

  1. python【力扣LeetCode算法题库】面试题62- 圆圈中最后剩下的数字(约瑟夫环)
  2. SAP CRM 和 SAP Cloud for Customer 的表格列项目宽度调整的原理介绍
  3. Tax debug and BP number external generation
  4. PhotoShop更改图片背景色
  5. 一道算法题跟大家分享
  6. (JAVA)CollectionDemo1
  7. 收藏 | YOLOX模型部署、优化及训练全过程
  8. iPhone 12系列接连出新问题:无法收短信等信息通知
  9. GenerateResource”任务意外失败的解决方法
  10. 微信网页开发 thinkphp5.0的try-catch和重定向
  11. numpy.loadtxt() 用法
  12. 小程序直播 OBS 画质_教你玩转微信小程序直播
  13. MS DTC服务无法启动解决方法
  14. 中国气象网 气象数据开放平台 API使用方法 (Android)(已废弃)
  15. Unity bug error CS1703: Multiple assemblies with equivalent identity have been imported...
  16. MATLAB几个误差参数说明
  17. 生命起源过程“消失环节”现形
  18. 【无标题】Android10 编译错误
  19. 《Linux基础三》用户和文件权限管理
  20. linux双系统怎么进tty,HI3556V200 Linux+Liteos双系统学习(4)----双系统通信 IPCM/virt_tty/sharefs...

热门文章

  1. 从后端看Vue-读《Vue.js技术内幕》
  2. 纽约时报:硅谷企业兵败中国 但硅谷文化已落地生根
  3. Informer--用于长序列时序预测【2021AAAI Best Paper】
  4. 编译原理分析器大作业之字幕分析器
  5. Elasticsearch7+SpringBoot实现简单查询及高亮分词查询
  6. 原创 | 机器学习在分子动力学领域顶会论文初探
  7. 为什么说密钥管理是数据安全体系的核心?
  8. zblog include html页面,龙三公子博客-Zblog添加自定义页面调用footer和header
  9. 漂流瓶语聊视频文字聊天模式app软件原生源码定制开发
  10. firebase分析_为什么我在下一个项目中不使用Firebase分析