目录
非ROS版本
配置
要在linux下使用realsense相机,需要首先配置librealsense。我的环境是Ubuntu18.04,相机是D435i相机。
librealsense的地址在点击这里。
但是自己编译的时候发现太慢了,根本不知道是卡住了,还是正常进行但是时间比较漫长。很麻烦,建议不要自己编译,而是直接用apt install 的方式来装,这样装又快又省事,官方也给了相关的说明,点击这里。
首先,加载key:
sudo apt-key adv --keyserver keys.gnupg.net --recv-key F6E65AC044F831AC80A06380C8B3A55A6F3EFCDE || sudo apt-key adv --keyserver hkp://keyserver.ubuntu.com:80 --recv-key F6E65AC044F831AC80A06380C8B3A55A6F3EFCDE
对于16.04系统,
sudo add-apt-repository "deb http://realsense-hw-public.s3.amazonaws.com/Debian/apt-repo xenial main" -u
对于18.04系统:
sudo add-apt-repository "deb http://realsense-hw-public.s3.amazonaws.com/Debian/apt-repo bionic main" -u
然后只要安装下面两个就可以了:
sudo apt-get install librealsense2-dkms
sudo apt-get install librealsense2-utils
上面这两个正常的网速来说,每个顶多半个小时。如果卡着很慢,最好是Ctrl+C掉重新来,不要一直等。
在装完之后,插上相机,输入这个指令就可以打开官方提供的GUI面板了:
realsense-viewer
不过,相机需要连接到USB3.0接口而不是2.0接口,否则打开后会报错。
使用
在GUI面板中可以以bag的形式保存拍摄的内容,相信很多人最关心的就是对这个bag的读取,或者说干脆自己通过代码操控相机,更重要的是把RGB图像和depth图像对齐起来,好从某个像素的位置处读取其对应的深度。
我写了一段Python代码,可以读取播放之前通过GUI面板保存的bag,或者实时通过相机拍摄记录视频(这种方式还可以指定图像的拍摄大小,以及拍摄的帧率)
另外还提供了两种功能:把深度图对齐到彩色图像,或者把彩色图像对齐到深度图像。
首先需要装一个包:
pip install pyrealsense2
然后具体代码如下:
#coding=utf-8
import pyrealsense2 as rs
import numpy as np
import cv2
#0:使用相机
# 1:使用API录制好的bag
USE_ROS_BAG=1
#0:彩色图像对齐到深度图;
# 1:深度图对齐到彩色图像
ALIGN_WAY=1
def Align_version(frames,align,show_pic=0):
# 对齐版本
aligned_frames = align.process(frames)
depth_frame_aligned = aligned_frames .get_depth_frame()
color_frame_aligned = aligned_frames .get_color_frame()
# if not depth_frame_aligned or not color_frame_aligned:
# continue
color_image_aligned = np.asanyarray(color_frame_aligned.get_data())
if USE_ROS_BAG:
color_image_aligned=cv2.cvtColor(color_image_aligned,cv2.COLOR_BGR2RGB)
depth_image_aligned = np.asanyarray(depth_frame_aligned.get_data())
depth_colormap_aligned = cv2.applyColorMap(cv2.convertScaleAbs(depth_image_aligned, alpha=0.05), cv2.COLORMAP_JET)
images_aligned = np.hstack((color_image_aligned, depth_colormap_aligned))
if show_pic:
cv2.imshow('aligned_images', images_aligned)
return color_image_aligned,depth_image_aligned,depth_colormap_aligned
def Unalign_version(frames,show_pic=0):
# 未对齐版本
# Wait for a coherent pair of frames: depth and color
frames = pipeline.wait_for_frames()
depth_frame = frames .get_depth_frame()
color_frame = frames .get_color_frame()
if not USE_ROS_BAG:
left_frame = frames.get_infrared_frame(1)
right_frame = frames.get_infrared_frame(2)
left_image = np.asanyarray(left_frame.get_data())
right_image = np.asanyarray(right_frame.get_data())
if show_pic:
cv2.imshow('left_images', left_image)
cv2.imshow('right_images', right_image)
# if not depth_frame or not color_frame:
# continue
color_image = np.asanyarray(color_frame.get_data())
print("color:",color_image.shape)
depth_image= np.asanyarray(depth_frame.get_data())
print("depth:",depth_image.shape)
#相机API录制的大小rosbag的rgb图像与depth图像不一致,用resize调整到一样大
if USE_ROS_BAG:
color_image=cv2.cvtColor(color_image,cv2.COLOR_BGR2RGB)
if ALIGN_WAY: #深度图对齐到彩色图像
depth_image=cv2.resize(depth_image,(color_image.shape[1],color_image.shape[0]))
else: #彩色图像对齐到深度图
color_image=cv2.resize(color_image,(depth_image.shape[1],depth_image.shape[0]))
# 上色
depth_colormap = cv2.applyColorMap(cv2.convertScaleAbs(depth_image, alpha=0.05), cv2.COLORMAP_JET)
# Stack both images horizontally
images = np.hstack((color_image, depth_colormap))
if show_pic:
cv2.imshow('images', images)
return color_image,depth_image,depth_colormap
if __name__ == "__main__":
# Configure depth and color streams
pipeline = rs.pipeline()
config = rs.config()
if USE_ROS_BAG:
config.enable_device_from_file("666.bag")#这是打开相机API录制的视频
else:
config.enable_stream(rs.stream.color, 640, 480, rs.format.bgr8, 30) #10、15或者30可选,20或者25会报错,其他帧率未尝试
config.enable_stream(rs.stream.depth, 640, 480, rs.format.z16, 30)
#左右双目
config.enable_stream(rs.stream.infrared, 1, 640, 480, rs.format.y8, 30)
config.enable_stream(rs.stream.infrared, 2, 640, 480, rs.format.y8, 30)
if ALIGN_WAY:
way=rs.stream.color
else:
way=rs.stream.depth
align = rs.align(way)
profile =pipeline.start(config)
depth_sensor = profile.get_device().first_depth_sensor()
depth_scale = depth_sensor.get_depth_scale()
print("scale:", depth_scale)
# 深度比例系数为: 0.0010000000474974513
try:
while True:
frames = pipeline.wait_for_frames()
color_image_aligned,depth_image_aligned,depth_colormap_aligned=Align_version(frames,align,show_pic=1)
color_image,depth_image,depth_colormap=Unalign_version(frames,show_pic=1)
#print(depth_image_aligned*depth_scale)
key = cv2.waitKey(1)
# Press esc or 'q' to close the image window
if key & 0xFF == ord('q') or key == 27:
cv2.destroyAllWindows()
break
finally:
# Stop streaming
pipeline.stop()
插上相机(或者把录好的bag放到同一目录下),修改USE_ROS_BAG和ALIGN_WAY,然后运行这个代码,就可以看到相机拍摄的图像啦。
注意:
1.函数Align_version和Unalign_version分别读取相机或bag的图像,前者还进行深度图与RGB图像的对齐。具体是谁对齐到谁,由变量ALIGN_WAY控制。
2.depth_scale是比例系数,用于在深度图像中直接取值以后,乘以这个系数,得到现实里实际的深度值。(即相机坐标系下的z值。)
这点很多用过深度相机的人也答不上来。即:深度相机采集到的深度,是场景点距离相机坐标系平面的深度,还是距离相机光心的距离?
换句话说,拿深度相机对准一面墙拍摄,现实里这面墙上的每个点距离相机的距离并不同(最近的是相机正前方,最远的是四个墙角)。而根据拍摄得到的深度图,这面墙上各个点进行深度取值,值是否相同?
这里揭晓答案:实验过的人才知道是相同的,相机内部已经进行过换算了。也就是说深度图中记录的深度并不是距离相机的直线距离,而是距离相机平面的垂直深度。
3.直接用相机拍,可以看到左右双目拍摄的结构光点的图像,用bag录好的是不行的。
4.show_pic是用于是否显示图片的变量,两个函数返回的三个变量,分别是彩色图像,深度图像,以及上色以后的深度图像(近处偏冷,远处偏暖)
5.样例图如下:
将深度图对齐到RGB:
上面是没有对齐的版本,可以看出RGB和depth中的手不在同一位置,大小也不同;
下面是对齐后的版本,可以看出RGB和depth中的手的位置已经对齐。
将RGB对齐到深度图:
上面是没有对齐的版本,可以看出RGB和depth中手不在同一位置,大小也不同;
而下面是对齐后的版本,可以看出RGB已经被对齐到了深度图,其中没有深度值的地方也就不再显示RGB值。(从这个里我们可以看出RGB相机和Depth相机的感受视野是不一样的。
5.我们以上图的手的图像为例,发现深度图的手部存在重影。
(其实不是重影,从下面RGB对齐到的地方可以看出,这个地方没有采集到深度。)
为什么会这样?这不是相机坏了或者是代码有问题。这个叫“残影”。
官方的解答是:用立体视觉生成的深度数据将左成像器用作立体匹配的参考,从而在左成像器和右成像器的视场中形成一个非重叠区域,在该区域中,帧的左边缘将没有深度数据。与距离较远的场景相比,较近的场景会导致更宽的无效深度范围。
这点可以参考博客:
Intel Realsense D435 深度图为什么会出现残影?(Invalid Depth Band 无效深度带)(黑洞)
ROS版本
如果你准备用在机器人上,可以使用ros驱动。
以下内容默认你掌握ros的基本使用,否则通过上面的方法尝试去解决。
ros的安装我这里不介绍,自行搜索ros安装教程,以20.04ubuntu系统的noetic为例。
装好ros以后,安装realsense的ros驱动:
sudo apt-get install ros-noetic-realsense2-camera
sudo apt-get install ros-noetic-realsense2-description
装好以后,到/opt/ros/noetic/share/realsense2_camera/launch 这个路径下,可以看看这个相机驱动自带哪些launch文件。
我这里提供一个luanch文件供启动:
<launch>
<arg name="serial_no" default=""/>
<arg name="json_file_path" default=""/>
<arg name="camera" default="camera"/>
<arg name="tf_prefix" default="$(arg camera)"/>
<arg name="fisheye_width" default="640"/>
<arg name="fisheye_height" default="480"/>
<arg name="enable_fisheye" default="true"/>
<arg name="depth_width" default="640"/>
<arg name="depth_height" default="480"/>
<arg name="enable_depth" default="true"/>
<arg name="infra_width" default="640"/>
<arg name="infra_height" default="480"/>
<arg name="enable_infra1" default="true"/>
<arg name="enable_infra2" default="true"/>
<arg name="color_width" default="640"/>
<arg name="color_height" default="480"/>
<arg name="enable_color" default="true"/>
<arg name="fisheye_fps" default="30"/>
<arg name="depth_fps" default="30"/>
<arg name="infra_fps" default="30"/>
<arg name="color_fps" default="30"/>
<arg name="gyro_fps" default="400"/>
<arg name="accel_fps" default="250"/>
<arg name="enable_gyro" default="true"/>
<arg name="enable_accel" default="true"/>
<arg name="enable_pointcloud" default="true"/>
<arg name="enable_sync" default="true"/>
<arg name="align_depth" default="true"/>
<arg name="filters" default=""/>
<group ns="$(arg camera)">
<include file="$(find realsense2_camera)/launch/includes/nodelet.launch.xml">
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
<arg name="serial_no" value="$(arg serial_no)"/>
<arg name="json_file_path" value="$(arg json_file_path)"/>
<arg name="enable_pointcloud" value="$(arg enable_pointcloud)"/>
<arg name="enable_sync" value="$(arg enable_sync)"/>
<arg name="align_depth" value="$(arg align_depth)"/>
<arg name="fisheye_width" value="$(arg fisheye_width)"/>
<arg name="fisheye_height" value="$(arg fisheye_height)"/>
<arg name="enable_fisheye" value="$(arg enable_fisheye)"/>
<arg name="depth_width" value="$(arg depth_width)"/>
<arg name="depth_height" value="$(arg depth_height)"/>
<arg name="enable_depth" value="$(arg enable_depth)"/>
<arg name="color_width" value="$(arg color_width)"/>
<arg name="color_height" value="$(arg color_height)"/>
<arg name="enable_color" value="$(arg enable_color)"/>
<arg name="infra_width" value="$(arg infra_width)"/>
<arg name="infra_height" value="$(arg infra_height)"/>
<arg name="enable_infra1" value="$(arg enable_infra1)"/>
<arg name="enable_infra2" value="$(arg enable_infra2)"/>
<arg name="fisheye_fps" value="$(arg fisheye_fps)"/>
<arg name="depth_fps" value="$(arg depth_fps)"/>
<arg name="infra_fps" value="$(arg infra_fps)"/>
<arg name="color_fps" value="$(arg color_fps)"/>
<arg name="gyro_fps" value="$(arg gyro_fps)"/>
<arg name="accel_fps" value="$(arg accel_fps)"/>
<arg name="enable_gyro" value="$(arg enable_gyro)"/>
<arg name="enable_accel" value="$(arg enable_accel)"/>
<arg name="filters" value="$(arg filters)"/>
</include>
</group>
</launch>
可以看到其中
<arg name="enable_pointcloud" default="true"/>
<arg name="enable_sync" default="true"/>
<arg name="align_depth" default="true"/>
这三句比较重要,enable_pointcloud 表示 会发布一个"camera_color_optical_frame"坐标系下的点云, align_depth 会对齐深度图和rgb图像。
其中,/camera/color/image_raw 话题是 RGB图像,/camera/aligned_depth_to_color/image_raw是对齐到RGB图像的depth图像。使用时只要监听这两个图像的话题即可,并且深度部分的单位是毫米。