DepthAI v2 has been superseded by DepthAI v3. You are viewing legacy documentation.
此页面由 AI 自动翻译。查看英文原版
DepthAI 教程
DepthAI API 参考

本页目录

  • 关键概念
  • 演示
  • 设置
  • 源代码

点云可视化

本示例演示了如何使用 DepthAI 和 Open3D 可视化设备上创建的点云。它从 OAK 设备捕获彩色和深度数据,将它们组合起来创建彩色点云,并在实时显示。FPS 计数器包含在内,用于监控性能。

关键概念

  • 使用 DepthAI API 捕获同步的彩色和深度帧。
  • 创建带有彩色数据的点云以进行可视化。
  • 使用 Open3D 实时可视化点云。
  • 实现 FPS 计数器以监控应用程序的性能。

演示

可视化点云

设置

如果您使用的是 Python,请确保您的 Python 环境中已安装 DepthAI 和 Open3D:
Command Line
1python3 -m pip install depthai open3d
如果尚未安装 Open3D,脚本将提示您安装它。

源代码

该示例使用彩色和单色摄像头以及立体深度节点初始化 DepthAI 管道以生成深度信息。然后,它创建一个点云节点并将其配置为稀疏点云生成。该脚本使用 Open3D 可视化此点云,其中每个点的颜色对应于 RGB 摄像头捕获的彩色图像。

Python

Python
GitHub
1#!/usr/bin/env python3
2
3import depthai as dai
4from time import sleep
5import numpy as np
6import cv2
7import time
8import sys
9try:
10    import open3d as o3d
11except ImportError:
12    sys.exit("Critical dependency missing: Open3D. Please install it using the command: '{} -m pip install open3d' and then rerun the script.".format(sys.executable))
13
14FPS = 30
15class FPSCounter:
16    def __init__(self):
17        self.frameCount = 0
18        self.fps = 0
19        self.startTime = time.time()
20
21    def tick(self):
22        self.frameCount += 1
23        if self.frameCount % 10 == 0:
24            elapsedTime = time.time() - self.startTime
25            self.fps = self.frameCount / elapsedTime
26            self.frameCount = 0
27            self.startTime = time.time()
28        return self.fps
29
30pipeline = dai.Pipeline()
31camRgb = pipeline.create(dai.node.ColorCamera)
32monoLeft = pipeline.create(dai.node.MonoCamera)
33monoRight = pipeline.create(dai.node.MonoCamera)
34depth = pipeline.create(dai.node.StereoDepth)
35pointcloud = pipeline.create(dai.node.PointCloud)
36sync = pipeline.create(dai.node.Sync)
37xOut = pipeline.create(dai.node.XLinkOut)
38xOut.input.setBlocking(False)
39
40
41camRgb.setResolution(dai.ColorCameraProperties.SensorResolution.THE_1080_P)
42camRgb.setBoardSocket(dai.CameraBoardSocket.CAM_A)
43camRgb.setIspScale(1,3)
44camRgb.setFps(FPS)
45
46monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P)
47monoLeft.setCamera("left")
48monoLeft.setFps(FPS)
49monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P)
50monoRight.setCamera("right")
51monoRight.setFps(FPS)
52
53depth.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_DENSITY)
54depth.initialConfig.setMedianFilter(dai.MedianFilter.KERNEL_7x7)
55depth.setLeftRightCheck(True)
56depth.setExtendedDisparity(False)
57depth.setSubpixel(True)
58depth.setDepthAlign(dai.CameraBoardSocket.CAM_A)
59
60monoLeft.out.link(depth.left)
61monoRight.out.link(depth.right)
62depth.depth.link(pointcloud.inputDepth)
63camRgb.isp.link(sync.inputs["rgb"])
64pointcloud.outputPointCloud.link(sync.inputs["pcl"])
65sync.out.link(xOut.input)
66xOut.setStreamName("out")
67
68
69
70
71with dai.Device(pipeline) as device:
72    isRunning = True
73    def key_callback(vis, action, mods):
74        global isRunning
75        if action == 0:
76            isRunning = False
77
78    q = device.getOutputQueue(name="out", maxSize=4, blocking=False)
79    vis = o3d.visualization.VisualizerWithKeyCallback()
80    vis.create_window()
81    vis.register_key_action_callback(81, key_callback)
82    pcd = o3d.geometry.PointCloud()
83    coordinateFrame = o3d.geometry.TriangleMesh.create_coordinate_frame(size=1000, origin=[0,0,0])
84    vis.add_geometry(coordinateFrame)
85
86    first = True
87    fpsCounter = FPSCounter()
88    while isRunning:
89        inMessage = q.get()
90        inColor = inMessage["rgb"]
91        inPointCloud = inMessage["pcl"]
92        cvColorFrame = inColor.getCvFrame()
93        # Convert the frame to RGB
94        cvRGBFrame = cv2.cvtColor(cvColorFrame, cv2.COLOR_BGR2RGB)
95        fps = fpsCounter.tick()
96        # Display the FPS on the frame
97        cv2.putText(cvColorFrame, f"FPS: {fps:.2f}", (10, 30), cv2.FONT_HERSHEY_SIMPLEX, 1, (0, 0, 255), 2)
98        cv2.imshow("color", cvColorFrame)
99        key = cv2.waitKey(1)
100        if key == ord('q'):
101            break
102        if inPointCloud:
103            t_before = time.time()
104            points = inPointCloud.getPoints().astype(np.float64)
105            pcd.points = o3d.utility.Vector3dVector(points)
106            colors = (cvRGBFrame.reshape(-1, 3) / 255.0).astype(np.float64)
107            pcd.colors = o3d.utility.Vector3dVector(colors)
108            if first:
109                vis.add_geometry(pcd)
110                first = False
111            else:
112                vis.update_geometry(pcd)
113        vis.poll_events()
114        vis.update_renderer()
115    vis.destroy_window()

C++

1#include <iostream>
2#include <opencv2/opencv.hpp>
3
4#include "depthai/depthai.hpp"
5
6int main() {
7    auto pipeline = dai::Pipeline();
8    auto monoLeft = pipeline.create<dai::node::MonoCamera>();
9    auto monoRight = pipeline.create<dai::node::MonoCamera>();
10    auto depth = pipeline.create<dai::node::StereoDepth>();
11    auto pointcloud = pipeline.create<dai::node::PointCloud>();
12    auto xout = pipeline.create<dai::node::XLinkOut>();
13    auto xoutDepth = pipeline.create<dai::node::XLinkOut>();
14
15    monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P);
16    monoLeft->setCamera("left");
17    monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P);
18    monoRight->setCamera("right");
19
20    // Create a node that will produce the depth map (using disparity output as
21    // it's easier to visualize depth this way)
22    depth->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
23    // Options: MEDIAN_OFF, KERNEL_3x3, KERNEL_5x5, KERNEL_7x7 (default)
24    depth->initialConfig.setMedianFilter(dai::MedianFilter::KERNEL_7x7);
25    depth->setLeftRightCheck(true);
26    depth->setExtendedDisparity(false);
27    depth->setSubpixel(true);
28
29    xout->setStreamName("out");
30    xoutDepth->setStreamName("depth");
31
32    monoLeft->out.link(depth->left);
33    monoRight->out.link(depth->right);
34    depth->depth.link(pointcloud->inputDepth);
35    depth->disparity.link(xoutDepth->input);
36    pointcloud->outputPointCloud.link(xout->input);
37    pointcloud->initialConfig.setSparse(true);
38
39    auto viewer = std::make_unique<pcl::visualization::PCLVisualizer>("Cloud Viewer");
40    bool first = true;
41
42    dai::Device device(pipeline);
43
44    auto q = device.getOutputQueue("out", 8, false);
45    auto qDepth = device.getOutputQueue("depth", 8, false);
46    long counter = 0;
47    while(true) {
48        std::cout << "Waiting for data" << std::endl;
49        auto depthImg = qDepth->get<dai::ImgFrame>();
50        auto pclMsg = q->get<dai::PointCloudData>();
51        std::cout << "Got data" << std::endl;
52        if(!pclMsg) {
53            std::cout << "No data" << std::endl;
54            continue;
55        }
56
57        auto frame = depthImg->getCvFrame();
58        frame.convertTo(frame, CV_8UC1, 255 / depth->initialConfig.getMaxDisparity());
59        cv::imshow("depth", frame);
60        cv::waitKey(1);
61
62        if(pclMsg->getPoints().empty()) {
63            std::cout << "Empty point cloud" << std::endl;
64            continue;
65        }
66        std::cout << "Number of points: " << pclMsg->getPoints().size() << std::endl;
67        std::cout << "Min x: " << pclMsg->getMinX() << std::endl;
68        std::cout << "Min y: " << pclMsg->getMinY() << std::endl;
69        std::cout << "Min z: " << pclMsg->getMinZ() << std::endl;
70        std::cout << "Max x: " << pclMsg->getMaxX() << std::endl;
71        std::cout << "Max y: " << pclMsg->getMaxY() << std::endl;
72        std::cout << "Max z: " << pclMsg->getMaxZ() << std::endl;
73
74        pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = pclMsg->getPclData();
75        if(first) {
76            viewer->addPointCloud<pcl::PointXYZ>(cloud, "cloud");
77            first = false;
78        } else {
79            viewer->updatePointCloud(cloud, "cloud");
80        }
81
82        viewer->spinOnce(10);
83
84        if(viewer->wasStopped()) {
85            break;
86        }
87    }
88
89    return 0;
90}

需要帮助?

请前往 Discussion Forum 获取技术支持或提出您可能有的任何其他问题。