pyrealsense2 是 Intel® RealSense™ 深度相机官方 SDK 的 Python 绑定库,属于 librealsense 项目的一部分。它提供了对 RealSense 系列深度相机(如 D400 系列、L500 系列、SR300 等)的完整 Python 接口支持,使开发者能够通过 Python 快速访问深度相机的高级功能。
深度相机技术通过主动投射红外图案(结构光)或测量激光飞行时间(ToF)来获取场景的深度信息。RealSense 相机结合了传统的 RGB 成像和深度感知能力,在三维重建、SLAM、手势识别等领域有广泛应用。
pyrealsense2 的核心价值在于:
RealSense 相机在学术研究中被广泛使用,相关论文包括:
# 安装依赖
sudo apt-get install python3 python3-pip libgl1-mesa-glx libglfw3
# 安装pyrealsense2
pip install pyrealsense2
# 可选:安装开发版
pip install git+https://github.com/IntelRealSense/librealsense.git@master#subdirectory=wrappers/python
# 通过pip安装
pip install pyrealsense2
# 如果遇到权限问题,添加--user参数
pip install --user pyrealsense2
import pyrealsense2 as rs
print(rs.__version__) # 应输出类似2.54.1的版本号
import pyrealsense2 as rs
import numpy as np
import cv2
# 创建管道
pipeline = rs.pipeline()
# 创建配置对象
config = rs.config()
# 启用彩色和深度流
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(f"Depth Scale: {depth_scale}")
try:
while True:
# 等待一组帧(深度和彩色)
frames = pipeline.wait_for_frames()
# 获取深度帧和彩色帧
depth_frame = frames.get_depth_frame()
color_frame = frames.get_color_frame()
if not depth_frame or not color_frame:
continue
# 转换为numpy数组
depth_image = np.asanyarray(depth_frame.get_data())
color_image = np.asanyarray(color_frame.get_data())
# 应用颜色映射到深度图像(用于可视化)
depth_colormap = cv2.applyColorMap(
cv2.convertScaleAbs(depth_image, alpha=0.03),
cv2.COLORMAP_JET)
# 显示图像
cv2.imshow('Color', color_image)
cv2.imshow('Depth', depth_colormap)
if cv2.waitKey(1) == ord('q'):
break
finally:
# 停止管道
pipeline.stop()
cv2.destroyAllWindows()
# 创建点云对象
pc = rs.pointcloud()
points = rs.points()
while True:
frames = pipeline.wait_for_frames()
depth_frame = frames.get_depth_frame()
color_frame = frames.get_color_frame()
# 生成点云
points = pc.calculate(depth_frame)
pc.map_to(color_frame)
# 获取顶点和纹理坐标
vtx = np.asanyarray(points.get_vertices())
tex = np.asanyarray(points.get_texture_coordinates())
# 此处可添加点云处理或可视化代码
# 例如使用Open3D进行可视化:
# import open3d as o3d
# pcd = o3d.geometry.PointCloud()
# pcd.points = o3d.utility.Vector3dVector(vtx)
# o3d.visualization.draw_geometries([pcd])
# 创建对齐对象(将深度对齐到彩色)
align_to = rs.stream.color
align = rs.align(align_to)
try:
while True:
frames = pipeline.wait_for_frames()
# 对齐帧
aligned_frames = align.process(frames)
# 获取对齐后的帧
aligned_depth_frame = aligned_frames.get_depth_frame()
color_frame = aligned_frames.get_color_frame()
# 后续处理...
finally:
pipeline.stop()
# 创建滤波器
dec_filter = rs.decimation_filter() # 降采样
spat_filter = rs.spatial_filter() # 空间平滑
temp_filter = rs.temporal_filter() # 时域滤波
# 应用滤波器链
filtered_frame = dec_filter.process(depth_frame)
filtered_frame = spat_filter.process(filtered_frame)
filtered_frame = temp_filter.process(filtered_frame)
问题描述:RuntimeError: No device connected
解决方案:
lsusb
确认设备被识别sudo cp config/99-realsense-libusb.rules /etc/udev/rules.d/
sudo udevadm control --reload-rules && udevadm trigger
问题描述:彩色和深度帧不同步
解决方案:
cfg.enable_stream(rs.stream.depth, preset=rs.option.inter_cam_sync_mode, value=1)
优化方案:
sensor = profile.get_device().first_depth_sensor()
sensor.set_option(rs.option.visual_preset, 3) # 3 = High Accuracy
问题描述:帧率低,延迟高
优化技巧:
import threading
class FrameProcessor:
def __init__(self):
self.latest_frames = None
def callback(self, frame):
self.latest_frames = frame
processor = FrameProcessor()
pipeline.start(config, processor.callback)
结合Open3D或PCL实现实时表面重建:
import open3d as o3d
# 创建可视化窗口
vis = o3d.visualization.Visualizer()
vis.create_window()
# 主循环中更新点云
pcd = o3d.geometry.PointCloud()
while True:
# 获取点云数据...
pcd.points = o3d.utility.Vector3dVector(vtx)
vis.update_geometry(pcd)
vis.poll_events()
vis.update_renderer()
结合MediaPipe实现实时姿态估计:
import mediapipe as mp
mp_pose = mp.solutions.pose
pose = mp_pose.Pose(min_detection_confidence=0.5)
while True:
# 获取彩色帧...
results = pose.process(color_image)
if results.pose_landmarks:
# 获取3D关节点坐标(结合深度数据)
landmarks = results.pose_landmarks.landmark
hip_z = depth_frame.get_distance(
int(landmarks[mp_pose.PoseLandmark.LEFT_HIP].x * width),
int(landmarks[mp_pose.PoseLandmark.LEFT_HIP].y * height))
# 结合深度信息的手势识别
def detect_gesture(depth_frame, hand_landmarks):
# 计算手掌深度
wrist_depth = depth_frame.get_distance(
int(hand_landmarks.landmark[0].x * width),
int(hand_landmarks.landmark[0].y * height))
# 计算手指伸展程度
finger_tips = [4,8,12,16,20] # 指尖关节点索引
extended = 0
for tip in finger_tips:
# 判断手指是否伸展...
pass
return gesture_mapping[extended]
对于多RealSense相机系统:
# 配置主从相机同步
master = rs.config()
master.enable_device('serial_number_1')
master.enable_stream(rs.stream.depth, preset=rs.option.inter_cam_sync_mode, value=1)
slave = rs.config()
slave.enable_device('serial_number_2')
slave.enable_stream(rs.stream.depth, preset=rs.option.inter_cam_sync_mode, value=2)
class CustomProcessingBlock(rs.processing_block):
def __init__(self):
super().__init__(self.process)
def process(self, frame):
# 自定义帧处理逻辑
data = np.asanyarray(frame.get_data())
processed_data = custom_algorithm(data)
new_frame = rs.frame(processed_data)
self.frame_queue.enqueue(new_frame)
# 使用自定义处理块
custom_block = CustomProcessingBlock()
pipeline = rs.pipeline()
pipeline.start(config, custom_block)
rs-fw-update
工具更新固件rs-depth-quality
工具评估深度质量# 安装RealSense ROS包
sudo apt-get install ros-$ROS_DISTRO-realsense2-camera
# 创建深度数据加载器
class RealSenseDataset(torch.utils.data.Dataset):
def __init__(self, pipeline, num_frames=100):
self.pipeline = pipeline
self.frames = []
def __getitem__(self, idx):
frames = self.pipeline.wait_for_frames()
depth = torch.from_numpy(np.asanyarray(
frames.get_depth_frame().get_data()))
return depth
使用Flask创建实时视频流:
from flask import Flask, Response
app = Flask(__name__)
def generate_frames():
while True:
frames = pipeline.wait_for_frames()
color_frame = frames.get_color_frame()
frame = np.asanyarray(color_frame.get_data())
ret, buffer = cv2.imencode('.jpg', frame)
yield (b'--frame\r\n'
b'Content-Type: image/jpeg\r\n\r\n' + buffer.tobytes() + b'\r\n')
@app.route('/video_feed')
def video_feed():
return Response(generate_frames(),
mimetype='multipart/x-mixed-replace; boundary=frame')
pyrealsense2 作为 Intel RealSense 相机的 Python 接口,为开发者提供了便捷的深度视觉开发工具。随着深度感知技术在AR/VR、机器人、智能监控等领域的广泛应用,掌握 RealSense 和 pyrealsense2 的使用将成为计算机视觉工程师的重要技能。
未来发展方向:
通过本指南介绍的基础到高级用法,开发者可以快速构建基于深度相机的创新应用,推动三维视觉技术的实际落地。