DepthAI
  • DepthAI Components
    • AprilTags
    • Benchmark
    • Camera
    • Calibration
    • DetectionNetwork
    • Events
    • FeatureTracker
    • Gate
    • HostNodes
    • ImageAlign
    • ImageManip
    • IMU
    • Misc
    • Model Zoo
    • NeuralDepth
    • NeuralNetwork
    • ObjectTracker
    • RecordReplay
    • RGBD
    • Script
    • SpatialDetectionNetwork
    • SpatialLocationCalculator
    • StereoDepth
    • Sync
    • VideoEncoder
    • Visualizer
    • Warp
    • RVC2-specific
  • Advanced Tutorials
  • API Reference
  • Tools
Software Stack

ON THIS PAGE

  • Demo
  • Pipeline
  • Source code

Depth Align

Supported on:RVC2RVC4
This example shows how to align the stereo depth map to the RGB frame to get RGB-D frames.

Demo

This example requires the DepthAI v3 API, see installation instructions.

Pipeline

Source code

Python

Python
GitHub
1#!/usr/bin/env python3
2
3import numpy as np
4import cv2
5import depthai as dai
6import time
7from datetime import timedelta
8FPS = 25.0
9
10RGB_SOCKET = dai.CameraBoardSocket.CAM_A
11LEFT_SOCKET = dai.CameraBoardSocket.CAM_B
12RIGHT_SOCKET = dai.CameraBoardSocket.CAM_C
13
14class FPSCounter:
15    def __init__(self):
16        self.frameTimes = []
17
18    def tick(self):
19        now = time.time()
20        self.frameTimes.append(now)
21        self.frameTimes = self.frameTimes[-10:]
22
23    def getFps(self):
24        if len(self.frameTimes) <= 1:
25            return 0
26        return (len(self.frameTimes) - 1) / (self.frameTimes[-1] - self.frameTimes[0])
27
28pipeline = dai.Pipeline()
29
30platform = pipeline.getDefaultDevice().getPlatform()
31
32# Define sources and outputs
33camRgb = pipeline.create(dai.node.Camera).build(RGB_SOCKET)
34left = pipeline.create(dai.node.Camera).build(LEFT_SOCKET)
35right = pipeline.create(dai.node.Camera).build(RIGHT_SOCKET)
36stereo = pipeline.create(dai.node.StereoDepth)
37sync = pipeline.create(dai.node.Sync)
38if platform == dai.Platform.RVC4:
39    align = pipeline.create(dai.node.ImageAlign)
40
41stereo.setExtendedDisparity(True)
42sync.setSyncThreshold(timedelta(seconds=1/(2*FPS)))
43
44rgbOut = camRgb.requestOutput(size = (1280, 960), fps = FPS, enableUndistortion=True)
45leftOut = left.requestOutput(size = (640, 400), fps = FPS)
46rightOut = right.requestOutput(size = (640, 400), fps = FPS)
47
48# Linking
49rgbOut.link(sync.inputs["rgb"])
50leftOut.link(stereo.left)
51rightOut.link(stereo.right)
52if platform == dai.Platform.RVC4:
53    stereo.depth.link(align.input)
54    rgbOut.link(align.inputAlignTo)
55    align.outputAligned.link(sync.inputs["depth_aligned"])
56else:
57    stereo.depth.link(sync.inputs["depth_aligned"])
58    rgbOut.link(stereo.inputAlignTo)
59
60queue = sync.out.createOutputQueue()
61
62def colorizeDepth(frameDepth):
63    invalidMask = frameDepth == 0
64    # Log the depth, minDepth and maxDepth
65    try:
66        minDepth = np.percentile(frameDepth[frameDepth != 0], 3)
67        maxDepth = np.percentile(frameDepth[frameDepth != 0], 95)
68        logDepth = np.zeros_like(frameDepth, dtype=np.float32)
69        np.log(frameDepth, where=frameDepth != 0, out=logDepth)
70        logMinDepth = np.log(minDepth)
71        logMaxDepth = np.log(maxDepth)
72        np.nan_to_num(logDepth, copy=False, nan=logMinDepth)
73        # Clip the values to be in the 0-255 range
74        logDepth = np.clip(logDepth, logMinDepth, logMaxDepth)
75
76        # Interpolate only valid logDepth values, setting the rest based on the mask
77        depthFrameColor = np.interp(logDepth, (logMinDepth, logMaxDepth), (0, 255))
78        depthFrameColor = np.nan_to_num(depthFrameColor)
79        depthFrameColor = depthFrameColor.astype(np.uint8)
80        depthFrameColor = cv2.applyColorMap(depthFrameColor, cv2.COLORMAP_JET)
81        # Set invalid depth pixels to black
82        depthFrameColor[invalidMask] = 0
83    except IndexError:
84        # Frame is likely empty
85        depthFrameColor = np.zeros((frameDepth.shape[0], frameDepth.shape[1], 3), dtype=np.uint8)
86    except Exception as e:
87        raise e
88    return depthFrameColor
89
90
91rgbWeight = 0.4
92depthWeight = 0.6
93
94
95def updateBlendWeights(percentRgb):
96    """
97    Update the rgb and depth weights used to blend depth/rgb image
98
99    @param[in] percent_rgb The rgb weight expressed as a percentage (0..100)
100    """
101    global depthWeight
102    global rgbWeight
103    rgbWeight = float(percentRgb) / 100.0
104    depthWeight = 1.0 - rgbWeight
105
106
107# Connect to device and start pipeline
108with pipeline:
109    pipeline.start()
110
111    # Configure windows; trackbar adjusts blending ratio of rgb/depth
112    windowName = "rgb-depth"
113
114    # Set the window to be resizable and the initial size
115    cv2.namedWindow(windowName, cv2.WINDOW_NORMAL)
116    cv2.resizeWindow(windowName, 1280, 720)
117    cv2.createTrackbar(
118        "RGB Weight %",
119        windowName,
120        int(rgbWeight * 100),
121        100,
122        updateBlendWeights,
123    )
124    fpsCounter = FPSCounter()
125    while True:
126        messageGroup = queue.get()
127        fpsCounter.tick()
128        assert isinstance(messageGroup, dai.MessageGroup)
129        frameRgb = messageGroup["rgb"]
130        assert isinstance(frameRgb, dai.ImgFrame)
131        frameDepth = messageGroup["depth_aligned"]
132        assert isinstance(frameDepth, dai.ImgFrame)
133
134        # Blend when both received
135        if frameDepth is not None:
136            cvFrame = frameRgb.getCvFrame()
137            # Colorize the aligned depth
138            alignedDepthColorized = colorizeDepth(frameDepth.getFrame())
139            # Resize depth to match the rgb frame
140            cv2.imshow("Depth aligned", alignedDepthColorized)
141
142            if len(cvFrame.shape) == 2:
143                cvFrameUndistorted = cv2.cvtColor(cvFrame, cv2.COLOR_GRAY2BGR)
144            blended = cv2.addWeighted(
145                cvFrame, rgbWeight, alignedDepthColorized, depthWeight, 0
146            )
147            cv2.putText(
148                blended,
149                f"FPS: {fpsCounter.getFps():.2f}",
150                (10, 30),
151                cv2.FONT_HERSHEY_SIMPLEX,
152                1,
153                (255, 255, 255),
154                2,
155            )
156            cv2.imshow(windowName, blended)
157
158        key = cv2.waitKey(1)
159        if key == ord("q"):
160            break

C++

1#include <chrono>
2#include <cmath>
3#include <deque>
4#include <iostream>
5#include <opencv2/opencv.hpp>
6#include <optional>
7#include <string>
8#include <vector>
9
10#include "depthai/depthai.hpp"
11
12constexpr float FPS = 25.0f;
13
14const dai::CameraBoardSocket RGB_SOCKET = dai::CameraBoardSocket::CAM_A;
15const dai::CameraBoardSocket LEFT_SOCKET = dai::CameraBoardSocket::CAM_B;
16const dai::CameraBoardSocket RIGHT_SOCKET = dai::CameraBoardSocket::CAM_C;
17
18// FPS Counter class
19class FPSCounter {
20   public:
21    void tick() {
22        auto now = std::chrono::steady_clock::now();
23        frameTimes.push_back(now);
24        while(frameTimes.size() > 10) {
25            frameTimes.pop_front();
26        }
27    }
28
29    float getFps() {
30        if(frameTimes.size() <= 1) return 0.0f;
31        auto duration = std::chrono::duration_cast<std::chrono::duration<float>>(frameTimes.back() - frameTimes.front()).count();
32        return (frameTimes.size() - 1) / duration;
33    }
34
35   private:
36    std::deque<std::chrono::steady_clock::time_point> frameTimes;
37};
38
39// Depth colorization function from detection_network_remap.cpp
40cv::Mat colorizeDepth(cv::Mat frameDepth) {
41    try {
42        // Early exit if no valid pixels
43        if(cv::countNonZero(frameDepth) == 0) {
44            return cv::Mat::zeros(frameDepth.rows, frameDepth.cols, CV_8UC3);
45        }
46
47        // Convert to float once
48        cv::Mat frameDepthFloat;
49        frameDepth.convertTo(frameDepthFloat, CV_32F);
50
51        double minVal, maxVal;
52        cv::minMaxLoc(frameDepthFloat, &minVal, &maxVal, nullptr, nullptr, frameDepthFloat > 0);
53
54        // Take log in-place
55        cv::log(frameDepthFloat, frameDepthFloat);
56        float logMinDepth = std::log(minVal);
57        float logMaxDepth = std::log(maxVal);
58
59        frameDepthFloat = (frameDepthFloat - logMinDepth) * (255.0f / (logMaxDepth - logMinDepth));
60
61        cv::Mat normalizedDepth;
62        frameDepthFloat.convertTo(normalizedDepth, CV_8UC1);
63
64        cv::Mat depthFrameColor;
65        cv::applyColorMap(normalizedDepth, depthFrameColor, cv::COLORMAP_JET);
66
67        // Mask invalid pixels
68        depthFrameColor.setTo(0, frameDepth == 0);
69
70        return depthFrameColor;
71
72    } catch(const std::exception& e) {
73        std::cerr << "Error in colorizeDepth: " << e.what() << std::endl;
74        return cv::Mat::zeros(frameDepth.rows, frameDepth.cols, CV_8UC3);
75    }
76}
77
78// Global blend weights
79float rgbWeight = 0.4f;
80float depthWeight = 0.6f;
81
82// Trackbar callback
83void updateBlendWeights(int percentRgb, void*) {
84    rgbWeight = static_cast<float>(percentRgb) / 100.0f;
85    depthWeight = 1.0f - rgbWeight;
86}
87
88int main() {
89    dai::Pipeline pipeline;
90
91    // Create and configure nodes
92    auto camRgb = pipeline.create<dai::node::Camera>();
93    camRgb->build(RGB_SOCKET);
94    auto left = pipeline.create<dai::node::Camera>();
95    left->build(LEFT_SOCKET);
96    auto right = pipeline.create<dai::node::Camera>();
97    right->build(RIGHT_SOCKET);
98    auto stereo = pipeline.create<dai::node::StereoDepth>();
99    auto sync = pipeline.create<dai::node::Sync>();
100
101    // Check if platform is RVC4 and create ImageAlign node if needed
102    auto platform = pipeline.getDefaultDevice()->getPlatform();
103    std::shared_ptr<dai::node::ImageAlign> align;
104    if(platform == dai::Platform::RVC4) {
105        align = pipeline.create<dai::node::ImageAlign>();
106    }
107
108    stereo->setExtendedDisparity(true);
109    sync->setSyncThreshold(std::chrono::duration<int64_t, std::nano>(static_cast<int64_t>(1e9 / (2.0 * FPS))));
110
111    // Configure outputs
112    auto rgbOut = camRgb->requestOutput(std::make_pair(1280, 960), dai::ImgFrame::Type::NV12, dai::ImgResizeMode::CROP, FPS, true);
113    auto leftOut = left->requestOutput(std::make_pair(640, 400), std::nullopt, dai::ImgResizeMode::CROP, FPS);
114    auto rightOut = right->requestOutput(std::make_pair(640, 400), std::nullopt, dai::ImgResizeMode::CROP, FPS);
115
116    // Link nodes
117    rgbOut->link(sync->inputs["rgb"]);
118    leftOut->link(stereo->left);
119    rightOut->link(stereo->right);
120
121    if(platform == dai::Platform::RVC4) {
122        stereo->depth.link(align->input);
123        rgbOut->link(align->inputAlignTo);
124        align->outputAligned.link(sync->inputs["depth_aligned"]);
125    } else {
126        stereo->depth.link(sync->inputs["depth_aligned"]);
127        rgbOut->link(stereo->inputAlignTo);
128    }
129
130    // Create output queue
131    auto queue = sync->out.createOutputQueue();
132
133    // Create and configure windows
134    const std::string windowName = "rgb-depth";
135    cv::namedWindow(windowName, cv::WINDOW_NORMAL);
136    cv::resizeWindow(windowName, 1280, 720);
137    cv::createTrackbar("RGB Weight %", windowName, nullptr, 100, updateBlendWeights);
138    cv::setTrackbarPos("RGB Weight %", windowName, static_cast<int>(rgbWeight * 100));
139
140    FPSCounter fpsCounter;
141
142    // Start pipeline
143    pipeline.start();
144
145    while(true) {
146        auto messageGroup = queue->get<dai::MessageGroup>();
147        fpsCounter.tick();
148
149        auto frameRgb = messageGroup->get<dai::ImgFrame>("rgb");
150        auto frameDepth = messageGroup->get<dai::ImgFrame>("depth_aligned");
151
152        if(frameDepth != nullptr) {
153            cv::Mat cvFrame = frameRgb->getCvFrame();
154
155            // Colorize depth
156            cv::Mat alignedDepthColorized = colorizeDepth(frameDepth->getFrame());
157            cv::imshow("Depth aligned", alignedDepthColorized);
158
159            // Convert grayscale to BGR if needed
160            if(cvFrame.channels() == 1) {
161                cv::cvtColor(cvFrame, cvFrame, cv::COLOR_GRAY2BGR);
162            }
163
164            // Blend frames
165            cv::Mat blended;
166            cv::addWeighted(cvFrame, rgbWeight, alignedDepthColorized, depthWeight, 0, blended);
167
168            // Add FPS text
169            cv::putText(blended, "FPS: " + std::to_string(fpsCounter.getFps()), cv::Point(10, 30), cv::FONT_HERSHEY_SIMPLEX, 1, cv::Scalar(255, 255, 255), 2);
170
171            cv::imshow(windowName, blended);
172        }
173
174        if(cv::waitKey(1) == 'q') {
175            break;
176        }
177    }
178
179    return 0;
180}

Need assistance?

Head over to Discussion Forum for technical support or any other questions you might have.