此页面由 AI 自动翻译。查看英文原版

配置立体深度

我们的 StereoDepth 节点 是高度可配置的,在本教程中,我们将介绍一些您可以进行的配置和故障排除,以获得最佳结果。本文档分为 7 章:
  1. 立体深度基础知识
  2. 立体深度预设规格
  3. 修复深度噪点
  4. 提高深度精度
  5. 近距离立体深度
  6. 远距离立体深度
  7. 修复点云噪点
立体视觉通过计算从略微不同位置拍摄的两张图像之间的视差来工作。立体视觉在很大程度上类似于我们的眼睛。我们的大脑(下意识地)根据左眼看到的与右眼看到的之间的差异来估算物体和场景的深度。在 OAK-D 相机上,情况完全相同;我们有左右相机(立体相机对),OAK 在设备上进行视差匹配以估算物体和场景的深度。视差是指立体对的左图像和右图像中两个对应点之间的距离。

从视差计算深度

我们首先看一下深度是如何计算的:
  • depth_cm - 以厘米为单位的深度
  • fx_px - 以像素为单位的 焦距
  • baseline_cm - 立体相机对的两个相机之间的距离
  • disparity_px - 以像素为单位的视差
以 OAK-D(7.5 厘米基线)为例,计算深度值,分辨率为 400P,视差为 50 像素:

焦距

焦距是相机镜头与图像传感器之间的距离。焦距越长,视场角 (FOV) 越窄。您可以从校准中读取相机的焦距(以像素为单位),请参阅此处的 校准转储 该值本身因相机型号和分辨率而异。推荐方法: 使用 ImgTransformations 来获取内参矩阵,因为它是应用于图像帧的实际变换的主要信息来源:
Python
1import depthai as dai
2
3# 从 ImgTransformations 获取内参(推荐)
4disparity = disparityQueue.get()  # 或 depthQueue.get()
5intrinsics = disparity.getTransformation().getSourceIntrinsicMatrix()
6print('焦距(像素):', intrinsics[0][0])
替代方法: 您也可以从校准中读取相机的焦距:
Python
1import depthai as dai
2
3with dai.Device() as device:
4  calibData = device.readCalibration()
5  intrinsics = calibData.getCameraIntrinsics(dai.CameraBoardSocket.CAM_C)
6  print('右单目相机焦距(像素):', intrinsics[0][0])
以像素为单位的焦距写在相机内参(intrinsics[0][0])中:

视差

视差和深度成反比。随着视差的减小,深度呈指数级增加,具体取决于基线和焦距。这意味着,如果视差值接近零,那么视差的小变化会产生大的深度变化。同样,如果视差值很大,那么视差的一些变化不会导致大的深度变化(精度更高)。这是 OAK-D(7.5 厘米基线距离)在 800P 分辨率下视差与深度的图表:
完整图表在此请注意,深度数据的值存储在 uint16 中,其中 0 表示距离无效/未知。

基线距离和焦距如何影响深度

从上面的深度公式可以看出,增加基线距离或增加焦距都会导致在相同视差下获得更远的深度,这意味着深度精度会更好。因此,要获得远距离深度感知,您可以增加基线距离和/或减小视场角

最小立体深度距离

如果近距离物体的深度结果看起来很奇怪,这很可能是因为它们低于设备的最小深度感知距离。您可以计算最小立体深度距离,例如 OAK-D 的基线为 7.5 厘米,焦距(像素)为 882.5 像素,并且视差(像素)的默认最大值为 95(请记住它是反比关系,因此最大值将产生最小结果)。我们有:
或大约 70 厘米。但是,通过以下选项可以将此距离减半(对于 OAK-D 约为 35 厘米):
  1. 将分辨率更改为 640x400,而不是标准的 1280x800。
  2. 启用扩展视差。
扩展视差模式将视差级别从标准的 96 像素增加到 191 像素,从而使最小深度减半。它通过计算原始 1280x720 和下采样 640x360 图像上的 96 像素视差来实现,然后将它们合并为 191 级视差。有关更多信息,请参阅 当前可配置块 中的扩展视差选项卡。使用前面的 OAK-D 示例,视差(像素)现在变为 190,最小距离为:
Python
1min_distance = focal_length_in_pixels * baseline / disparity_in_pixels = 882.5 * 7.5cm / 190 = 34.84cm
或大约 35 厘米。请参阅这些示例了解如何启用扩展视差。

将相机移近物体

查看 从视差计算深度 部分,从图表中可以清楚地看出,在 95 视差像素(近距离)处,视差像素之间的深度变化(例如 95->94)最低,因此深度精度最高
摄像头到物体的距离越远,深度精度呈指数级下降。请注意,启用 立体亚像素模式 后,即使在较远的距离也能获得更好的深度精度,但这仅在一定程度上有效。因此,总而言之,为了获得最佳深度精度您要测量的物体/场景尽可能靠近摄像头的 MinZ(最小深度感知距离)。您可以在 硬件文档 中找到每个设备的 MinZ 规格。

最大立体深度距离

最大深度感知距离取决于 基线距离和焦距如何影响深度。用于计算此距离的公式是一个近似值,如下所示:
Python
1Dm = (baseline/2) * tan((90 - HFOV / HPixels)*pi/180)
因此,使用此公式计算现有型号的理论最大距离为:
Python
1# 对于 OAK-D (7.5cm 基线)
2Dm = (7.5/2) * tan((90 - 71.9/1280)*pi/180) = 3825.03cm = 38.253
4# 对于 OAK-D-CM4 (9cm 基线)
5Dm = (9/2) * tan((90 - 71.9/1280)*pi/180) = 4590.04cm = 45.9
如果需要更高的远距离测量精度,请考虑启用亚像素视差或使用单目摄像头之间更大的基线距离。对于自定义基线,您可以考虑使用 OAK-FFC 设备或设计自己的具有所需基线的底板 PCB。有关更多信息,请参阅 当前可配置块 中“立体模式”选项卡下的亚像素视差。
StereoDepth 节点提供了几个配置文件预设,可用于快速为不同场景配置节点。每个预设都应用了一组特定的过滤器和参数,针对特定用例进行了优化。有关每个预设的 FPS 性能信息,请参阅 特定平台配置

RVC2

可用预设

RVC2 支持以下预设:
  • DEFAULT: 通用配置,设置均衡
  • ROBOTICS: 针对导航和障碍物检测进行了优化,无运动模糊
  • FACE: 针对人脸跟踪(短距离)进行了优化
  • HIGH_DETAIL: 设计用于捕捉场景中的精细细节和小物体,优先考虑最大细节,同时接受增加的噪点以增强特征可见性
  • FAST_DENSITY: 优先考虑高填充率和更快的处理速度
  • FAST_ACCURACY: 优先考虑高精度和更快的处理速度,但填充率较低

预设特定差异

有关过滤器的详细信息,请参阅 特定平台配置DEFAULT 预设:
  • 扩展视差:False
  • 亚像素:True(3 位)
  • 左右检查:True
  • 中值滤波器:KERNEL_7x7
  • 空间滤波器:enable=True, delta=3, holeFillingRadius=1
  • 斑点滤波器:enable=True, speckleRange=200
  • 时间滤波器:enable=True, alpha=0.5
  • 抽取滤波器:decimationFactor=2
  • 阈值滤波器:0 到 15 米(minRange=0, maxRange=15000)
  • 置信度阈值:15
ROBOTICS 预设:
  • 扩展视差:False
  • 亚像素:True(3 位)
  • 左右检查:True
  • 中值滤波器:KERNEL_7x7
  • 空间滤波器:enable=True, delta=20, holeFillingRadius=2
  • 斑点滤波器:enable=True, speckleRange=200
  • 时间滤波器:enable=False
  • 抽取滤波器:decimationFactor=2
  • 阈值滤波器:0 到 10 米(minRange=0, maxRange=10000)
  • 置信度阈值:15
FACE 预设:
  • 扩展视差:True
  • 亚像素:True(5 位)
  • 左右检查:True
  • 中值滤波器:MEDIAN_OFF
  • 空间滤波器:enable=True, delta=3, holeFillingRadius=1
  • 斑点滤波器:enable=True, speckleRange=200
  • 时间滤波器:enable=True, alpha=0.5
  • 抽取滤波器:decimationFactor=2
  • 阈值滤波器:0.03 到 3 米(minRange=30, maxRange=3000)
  • 置信度阈值:15
HIGH_DETAIL 预设:
  • 扩展视差:True
  • 亚像素:True(5 位)
  • 左右检查:True(阈值:5)
  • 中值滤波器:MEDIAN_OFF
  • 空间滤波器:enable=True, delta=3, holeFillingRadius=1
  • 斑点滤波器:enable=True, speckleRange=200
  • 时间滤波器:enable=True, alpha=0.5
  • 抽取滤波器:decimationFactor=2
  • 阈值滤波器:0 到 15 米(minRange=0, maxRange=15000)
  • 置信度阈值:55
FAST_DENSITY 预设:
  • 扩展视差:False
  • 亚像素:True(5 位)
  • 左右检查:True
  • 中值滤波器:MEDIAN_OFF
  • 空间滤波器:enable=False
  • 斑点滤波器:enable=False
  • 时间滤波器:enable=False
  • 抽取滤波器:decimationFactor=1(禁用)
  • 最大视差:3040.0(为提高速度而降低)
  • 置信度阈值:15
FAST_ACCURACY 预设:
  • 扩展视差:False
  • 亚像素:True(5 位)
  • 左右检查:True(阈值:5)
  • 中值滤波器:MEDIAN_OFF
  • 空间滤波器:enable=False
  • 斑点滤波器:enable=False
  • 时间滤波器:enable=False
  • 抽取滤波器:decimationFactor=1(禁用)
  • 最大视差:3040.0(为提高速度而降低)
  • 置信度阈值:55

通用参数

大多数参数在所有 RVC2 预设中保持一致:
  • 视差偏移0
  • 左右检查阈值10(变化:HIGH_DETAIL、FAST_ACCURACY 为 5
  • Census 变换
    • 启用均值模式:True
    • 噪点阈值偏移:1
    • 噪点阈值比例:1
  • 成本聚合
    • 除数:1
    • 水平惩罚 P1:250
    • 水平惩罚 P2:500
    • 垂直惩罚 P1:250
    • 垂直惩罚 P2:500
  • 后处理 - 亮度滤波器
    • 最小值:0
    • 最大值:256

RVC4

可用预设

RVC4 支持以下预设:
  • ACCURACY:优先考虑深度精度而非填充率,以实现精确的深度测量
  • DENSITY:优先考虑填充率和处理速度,以在更高的帧率下获得密集的深度图

预设特定差异

有关过滤器的详细信息,请参阅 特定平台配置ACCURACY 预设:
  • 扩展视差:True
  • 亚像素:True(4 位,RVC4 固定)
  • 软件左右检查:False
  • 中值滤波器:MEDIAN_OFF
  • 空间滤波器:enable=False
  • 斑点滤波器:enable=True, speckleRange=200, differenceThreshold=2
  • 时间滤波器:enable=False
  • 抽取滤波器:decimationFactor=1(禁用),decimationMode=NON_ZERO_MEAN
  • 自适应中值滤波器:enable=True, confidenceThreshold=200
  • 洞填充:enable=True, highConfidenceThreshold=240, fillConfidenceThreshold=251, minValidDisparity=1
  • 置信度阈值:97
  • 置信度指标:
    • 遮挡置信度权重:14
    • 运动矢量置信度权重:16
    • 运动矢量置信度阈值:1
    • 平坦度置信度权重:2
    • 平坦度置信度阈值:4
    • 平坦度覆盖:False
  • Census 变换:noiseThresholdOffset=0, noiseThresholdScale=84
  • 阈值滤波器:minRange=0, maxRange=65535
  • 亮度滤波器:minBrightness=0, maxBrightness=256
DENSITY 预设:
  • 扩展视差:True
  • 亚像素:True (4 位,RVC4 固定)
  • 软件左右检查:True (阈值:4)
  • 中值滤波器:KERNEL_5x5
  • 空间滤波器:enable=False
  • 斑点滤波器:enable=TruespeckleRange=200differenceThreshold=2
  • 时间滤波器:enable=False
  • 抽取滤波器:decimationFactor=1 (禁用),decimationMode=PIXEL_SKIPPING
  • 自适应中值滤波器:enable=TrueconfidenceThreshold=200
  • 填充空洞:enable=False
  • 置信度阈值:20
  • 置信度指标:
    • 遮挡置信度权重:28
    • 运动矢量置信度权重:0
    • 运动矢量置信度阈值:1
    • 平坦度置信度权重:4
    • 平坦度置信度阈值:4
    • 平坦度覆盖:False
  • Census 变换:noiseThresholdOffset=0noiseThresholdScale=-40
  • 阈值滤波器:minRange=0maxRange=65535
  • 亮度滤波器:minBrightness=-1maxBrightness=256

通用参数

大多数参数在所有 RVC4 预设中是一致的:
  • 亚像素:4 位 (RVC4 固定)
  • 扩展视差True
  • 空间滤波器enable=False
  • 斑点滤波器enable=TruespeckleRange=200differenceThreshold=2
  • 时间滤波器enable=False
  • 抽取滤波器decimationFactor=1 (禁用)
  • 自适应中值滤波器enable=TrueconfidenceThreshold=200
  • 阈值滤波器minRange=0maxRange=65535
我们注意到一些与立体深度质量相关的议题:

场景纹理

由于立体匹配算法的工作方式,被动立体深度需要场景中具有良好的纹理,否则深度图会很嘈杂/无效。低视觉兴趣的表面(几乎没有纹理的空白表面),例如墙壁或地板。解决方案: 我们的 OAK Pro 版本 OAK 相机具有板载 IR 激光点投影仪 它将数千个小点投射到场景中,这有助于立体匹配算法,因为它为场景提供了更多纹理。
我们使用的技术称为 ASV (传统主动立体视觉), 因为立体匹配在设备上执行的方式与被动立体 OAK-D 相同。

立体深度置信度阈值

在计算视差时,视差图中的每个像素都会 由立体匹配算法分配一个置信度值 0..255 此置信度分数是(如果,比如说,与 NN 置信度进行比较的话)倒置的:
  • 0 - 持有有效值的最大置信度
  • 255 - 最小置信度,因此值不正确的可能性更大
对于最终的视差图,会根据 置信度阈值进行过滤:置信度分数 大于阈值的像素将被视为无效,即它们的视差值 设置为零。您可以通过下面的 API 设置置信度阈值。这意味着通过置信度阈值,用户可以优先选择填充率或准确性

Python

Python
1# 创建 StereoDepth 节点
2stereo_depth = pipeline.create(dai.node.StereoDepth)
3stereo_depth.initialConfig.setConfidenceThreshold(threshold)
4
5# 或者,也可以设置 Stereo 预设模式:
6# 优先填充率,将置信度阈值设置为 245
7stereo_depth.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_DENSITY)
8# 优先准确性,将置信度阈值设置为 200
9stereo_depth.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_ACCURACY)

C++

C++
1// 创建 StereoDepth 节点
2auto stereo_depth = pipeline.create<dai::node::StereoDepth>();
3stereo_depth->initialConfig.setConfidenceThreshold(threshold);
4
5// 或者,也可以设置 Stereo 预设模式:
6// 优先填充率,将置信度阈值设置为 245
7stereo_depth->setDefaultProfilePreset(dai::node::StereoDepth::Preset::HIGH_DENSITY);
8// 优先准确性,将置信度阈值设置为 200
9stereo_depth->setDefaultProfilePreset(dai::node::StereoDepth::Preset::HIGH_ACCURACY);

立体相机对噪声

如果输入的左右图像有噪点,视差图也会有噪点。因此,良好深度的前提是高 IQ(参见 图像质量 文档)的左右立体图像。主动立体(OAK Pro 版本的 OAK 相机)在很大程度上可以缓解此问题,但对于被动立体 相机,您可以做一些事情来提高立体相机对的质量。建议使用单色(灰度)相机作为立体相机对,因为它们的量子效率 (QE) 更高,它们没有 彩色(Bayer)滤光片。更高的 QE 意味着相同的光量(光子)会产生更多的信号,从而提高信噪比 (SNR)。为了获得更好的低光性能,建议使用更长的曝光时间而不是更高的增益 (ISO),因为它会提高 SNR。有时 这意味着降低相机 FPS - 在 30 FPS 时,您可以使用 1/30 秒的曝光时间,在 15 FPS 时,您可以使用 1/15 秒的曝光时间,依此类推。有关更多信息,请参阅 低光照增加的灵敏度.另一个潜在的改进是调整传感器的 ISP 设置,例如色度和亮度去噪以及锐度。有关更多信息,请参阅 彩色相机 ISP 配置.

立体后处理滤波器

StereoDepth 节点 具有一些在设备上运行的后处理滤波器,可以启用它们来提高 视差图的质量。有关实现(API)详细信息,请参阅 StereoDepth 可配置块由于这些滤波器在设备上运行,因此会产生一些性能成本 这意味着在高分辨率帧(1MP)下,它们可能会成为 FPS 的瓶颈。为了降低成本,应考虑使用较低分辨率 的帧(例如 400P)和/或使用 抽取滤波器。由于额外的处理,这些 滤波器还会引入额外的延迟

中值滤波器

这是一个非边缘保持的中值滤波器,可用于减少噪点并平滑深度图。中值滤波器在硬件中实现,因此它是最快的滤波器。

斑点过滤器

斑点过滤器用于减少斑点噪声。斑点噪声是相邻视差/深度像素之间存在巨大方差的区域,斑点过滤器会尝试过滤该区域。

时间过滤器

时间过滤器旨在通过根据先前帧操纵每像素值来提高深度数据的持久性。该过滤器对数据执行单次传递,在调整深度值的同时更新跟踪历史记录。在像素数据缺失或无效的情况下,过滤器会使用用户定义的持久性模式来决定是否应使用存储的数据来改进缺失值。请注意,由于其依赖历史数据,该过滤器可能会引入明显的运动模糊/拖尾伪影,因此最适合静态场景

空间过滤器

空间边缘保持过滤器将用有效的相邻深度像素填充无效的深度像素。它执行一系列一维水平和垂直传递或迭代,以增强重建数据的平滑度。它基于这篇研究论文

亮度过滤器

亮度过滤器将过滤掉(通过设置为 0 使其无效)所有输入立体摄像头图像像素超出配置的最小/最大亮度阈值的所有深度像素。当您遇到高动态范围场景时,例如明亮的白天户外,或者通常当立体摄像头对可以直接看到光源时,此过滤器非常有用:
直接光源(顶灯)- 深度像素无效
它还有助于校正“伪影”,尤其是在您使用宽视场镜头并应用 alpha 参数时。当没有可用像素时,StereoDepth 节点默认会将该区域设置为 0(黑色),但可以使用 stereoDepth.setRectifyEdgeFillColor(int8) 进行更改。此黑色区域随后可以使用亮度过滤器进行无效化,如下所示:
在校正“伪影”处使深度无效化

阈值过滤器

阈值过滤器将过滤掉所有超出配置的最小/最大阈值的所有深度像素。在受控环境中,当您确切知道场景的距离时(例如,30 厘米 - 2 米),建议使用此过滤器。

抽值过滤器

抽值过滤器将对深度图进行子采样,这意味着它会降低深度场景的复杂性,并允许其他过滤器运行得更快。将 decimationFactor 设置为 2 会将 1280x800 的深度图缩小到 640x400。我们可以选择像素跳过、中值或平均抽值模式,后两种模式也有助于过滤。decimationFactor 1 会禁用该过滤器。它对于点云也非常有用。

过滤顺序

过滤器的顺序很重要,因为一个过滤器的输出是下一个过滤器的输入。过滤器的顺序是可自定义的,可以通过以下方式设置:
Python
1config.postProcessing.filteringOrder = [
2  dai.RawStereoDepthConfig.PostProcessing.Filter.TEMPORAL,
3  dai.RawStereoDepthConfig.PostProcessing.Filter.SPECKLE,
4  dai.RawStereoDepthConfig.PostProcessing.Filter.SPATIAL,
5  dai.RawStereoDepthConfig.PostProcessing.Filter.MEDIAN,
6  dai.RawStereoDepthConfig.PostProcessing.Filter.DECIMATION
7]
上一章我们关注了噪声,这不一定是深度不准确的唯一原因。有几种方法可以提高深度精度:

立体亚像素模式

首先让我们了解一下立体亚像素模式是什么以及它是如何工作的。 有关图像亚像素的解释,请参阅什么是亚像素?在计算视差深度时,立体匹配算法为每个视差像素分配一个“置信度”分数,这意味着深度图像的每个像素包含 96 字节(用于置信度)。如果您对所有这些成本值感兴趣,可以使用 stereoDepth.debugDispCostDump 输出,但请注意它是一个非常大的输出(例如,每帧 1280*800*96 => 98MB)。
立体亚像素模式将通过查看每个方向上 2 个相邻视差像素的置信度值来计算亚像素视差。在上面的示例图中,在正常模式下,StereoDepth 只会获得最大视差 = 34 像素,但在亚像素模式下,它会返回更多一点,例如 34.375 像素,因为像素 35 和 36 的置信度也很高。**简而言之:**立体亚像素模式应始终提供更准确的深度,但会消耗额外的硬件资源(请参阅立体深度 FPS了解影响)。

立体亚像素对分层的影响

默认的立体深度输出有 0..95 个视差像素,这将产生 96 个唯一的深度值。当使用点云表示并看到离散的“层”而不是平滑过渡时,这一点尤其明显:
这种分层在较远的距离尤其明显,因为这些层之间的距离呈指数级增长。但是,启用立体亚像素模式后,可以获得更多唯一的数值,从而产生更精细的深度步长,从而获得更平滑的点云。
亚像素小数位数唯一值数量
3754
41506
53010
可以通过将 stereoDepth.setSubpixelFractionalBits(int) 参数设置为 3、4 或 5 位来更改亚像素位数。
要获得准确的短距离深度,您首先需要遵循提高深度精度的步骤。对于大多数普通视场角、OV9282 OAK-D* 相机,您希望物体/场景距离相机约 70 厘米,此时误差低于 2%(具有良好的场景纹理),即 ± 1.5 厘米误差。但如何获得更好的深度精度,例如厘米级立体深度精度?正如我们在 基线距离和焦距如何影响深度中学到的, 我们希望有更近的基线距离和/或更窄的视场镜头。因此,对于短距离深度感知,我们建议使用 OAK-D SROAK-D ToF 因为它们具有 2 厘米的基线距离、800P 分辨率,非常适合高达 1 米的深度传感。回到 视差深度,最小深度感知 MinZ)由以下公式定义,其中视差为 95 像素(视差搜索的最大像素数):

如何获得更低的 MinZ

如果近距离物体的深度结果看起来很奇怪,这很可能是 因为它们低于 OAK 相机的 MinZ 距离。您可以通过以下任一方式获得更低的 OAK 相机 MinZ:最后两种选项可以同时启用,这将使最小深度设置为标准设置的 1/4,但在如此短的距离下,MinZ 可能受焦距限制。

降低分辨率以减小 MinZ

上面我们有一个 MinZ 的公式,通过降低分辨率,我们正在降低焦距(以像素为单位),所以让我们再次看一下公式:
如您所见,通过将分辨率降低 2 倍,我们将 MinZ 也降低了 2 倍。请注意,由于像素数量减少,深度精度(以厘米为单位)也会降低。

立体扩展视差模式

降低分辨率以减小 MinZ 非常相似, 扩展模式运行立体深度管道两次(因此消耗更多硬件资源);一次使用传递给 StereoDepth 节点的帧的分辨率, 一次使用分辨率缩小 2 倍,然后合并两个输出视差图。

立体压缩模式

视差压缩进行稀疏视差匹配:
  • 前 48 个像素逐像素匹配,意味着在更远的距离没有缺点
  • 接下来的 32 个像素每隔 2 个像素匹配一次,因此精度减半(在更近的距离)
  • 最后 16 个像素每隔 4 个像素匹配一次,因此精度减为四分之一(在最近的距离)。因为精度在最近的距离本身就是最好的,所以这是一个不错的权衡。
与扩展模式相比,压缩模式速度更快,因为它不需要执行两次视差匹配。请注意,压缩模式不能与扩展模式一起使用。
压缩 - 对精度的影响(75mm 基线,800P,普通视场角)
上面的图表可在 Google 表格 中找到。请注意,此图表适用于全像素视差, 启用亚像素模式后精度会更好(请参阅 立体深度精度文档)。
Python
1stereo = pipeline.create(dai.node.StereoDepth)
2cfg = stereo.initialConfig.get()
3# Enable companding mode
4cfg.costMatching.enableCompanding = True
5stereo.initialConfig.set(cfg)

视差偏移

在已知 MaxZ 的受控环境中,为了感知更近的深度范围,建议使用视差偏移,因为它不像其他两种方法那样降低深度精度。视差偏移将改变视差搜索的起点,这将显著降低 MaxZ,但也会降低 MinZ。视差偏移可以与扩展/亚像素/LR 检查模式结合使用。
左图显示了 OAK-D(7.5 厘米基线,800P 分辨率,约 70° 水平视场角)的最小和最大视差及深度,默认情况下(视差偏移=0)。请参阅 视差深度 由于硬件(立体块)具有固定的 95 像素视差搜索,DepthAI 将从 0 像素(深度=INF)搜索到 95 像素(深度=71 厘米)。限制右图显示了相同的情况,但视差偏移设置为 30 像素。这意味着视差搜索将从 30 像素(深度=2.2 米)到 125 像素(深度=50 厘米)。这也意味着深度在短距离内将非常精确(理论上低于 5 毫米的深度误差)。
  • 由于视差与深度的反比关系,随着视差偏移的增加,MaxZ 的降低速度远快于 MinZ。因此,建议不要使用大于实际需要的视差偏移
  • 以这种方式减小 MinZ 的权衡是,距离 MaxZ 更远距离的物体将不可见
  • 由于上述原因,我们仅建议在已知 MaxZ 时使用视差偏移,例如将深度相机安装在桌子上,向下指向桌面表面。
  • 输出的视差图未扩展,仅深度图。因此,如果视差偏移设置为 50,并且获得的视差值为 90,则实际视差为 140。
与扩展视差相比,视差偏移:
  • (+) 速度更快,因为它不需要额外的计算,这意味着也没有额外的延迟
  • (-) 降低了 MaxZ(显著),而扩展视差仅降低 MinZ。
视差偏移可以与扩展视差结合使用。
method

depthai.StereoDepthConfig.setDisparityShift

近距离深度限制

由于深度是从视差计算出来的,而视差需要像素重叠,因此在左单目相机的左侧和右单目相机的右侧本质上存在一个垂直带,由于只有一个立体相机可以看到,因此无法计算深度。该带在下图中用 B 标记。
在非常近的距离,即使启用了 立体扩展视差模式 降低分辨率,您也会注意到 这个无效深度像素的垂直带。图中变量的含义:
  • BL [cm] - 立体摄像机的基线。
  • Dv [cm] - 两台摄像机都能看到物体的最小距离(因此可以计算深度)。
  • B [pixels] - 无法计算深度的条带宽度。
  • W [pixels] - 单目摄像机的像素宽度或水平像素数量,在其他公式中也称为 HPixels
  • D [cm] - 从相机平面到物体的距离(请参阅图像 测量真实世界物体尺寸)。
  • F [cm] - 在距离 D 处的图像宽度。
https://user-images.githubusercontent.com/59799831/135310972-c37ba40b-20ad-4967-92a7-c71078bcef99.png
使用 tan 函数,可以得到以下公式:
  • F = 2 * D * tan(HFOV/2)
  • Dv = (BL/2) * tan(90 - HFOV/2)
为了得到 B,我们可以再次使用 tan 函数(与计算 F 相同),但这次我们还必须将其乘以 WF 的比率,以便将单位转换为像素。这得到了以下公式:
示例:如果我们使用 OAK-D,其 HFOV 为 72°,基线(BL)为 7.5 cm,并且使用了 640x400 (400P) 分辨率,因此 W = 640,并且一个物体距离为 D = 100 cm,我们可以按以下方式计算 B
Command Line
1Dv = 7.5 / 2 * tan(90 - 72/2) = 3.75 * tan(54°) = 5.16 cm
2B = 640 * 5.16 / 100 = 33 # pixels
计算和图像的功劳归于我们的社区成员 gregflurry,他在论坛帖子中完成。

测量真实世界物体尺寸

由于深度图包含 Z 距离,因此与相机平行的物体可以准确地进行标准测量。对于不平行的物体,可以使用欧几里得距离计算。请参考以下内容:
software/depthai/nodes//Euclidian_distance_fig.webp
在运行例如 RGB & Yolo with spatial data 示例时,您可以使用下面的代码计算到检测到的对象的 XYZ 坐标距离(在示例代码行 143 之后):
Python
1distance = math.sqrt(detection.spatialCoordinates.x ** 2 + detection.spatialCoordinates.y ** 2 + detection.spatialCoordinates.z ** 2) # mm
为了获得准确的长距离深度,我们应首先检查 提高深度精度 步骤,因为它们 尤其适用于长距离深度。对于长距离深度,我们还应考虑以下几点:
  • 窄视场镜头
  • 立体摄像机之间的宽基线距离
因此,对于长距离,我们建议使用 OAK-D Long Range 它具有(更大的)15cm 基线距离和 60° 的默认视场。 它具有 M12 接口镜头 因此用户可以用更窄(或更宽)的视场镜头替换它们。
对于噪点点云,我们建议几种方法:

点云的抽取滤波器

抽取滤波器 点云尤其有用,您实际上不希望有 100 万个点(尽管听起来对营销很有吸引力),因为它处理的数据量太大。 抽取滤波器在此处很有帮助,在使用点云时应启用它。使用点云的抽取滤波器时,应启用中值/平均模式抽取,因为它将提供额外的过滤 (与像素跳过模式相比)。它还可以使其他 立体后处理滤波器 更快,因为需要处理的数据更少。

使拐角周围的像素无效

拐角周围通常存在无效/噪点像素,我们 注意到一些客户会预防性地使深度图像拐角周围的几个像素(例如 3 个)无效。我们还建议启用 亮度滤波器 特别是由于校正“伪影”。

主机端点云过滤

除了设备端的 立体后处理滤波器 外, 我们还建议运行主机端点云过滤(例如使用 Open3DPCL 库)。我们特别建议使用点云体素化和移除统计异常值技术, 此处有示例 用于这两种技术。