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