Depth Preview¶
This example shows how to set the SGBM (semi-global-matching) disparity-depth node, connects over XLink to transfer the results to the host real-time, and displays the depth map in OpenCV. Note that disparity is used in this case, as it colorizes in a more intuitive way. Below is also a preview of using different median filters side-by-side on a depth image. There are 3 depth modes which you can select inside the code:
lr_check: used for better occlusion handling. For more information click here
extended_disparity: suitable for short range objects. For more information click here
subpixel: suitable for long range. For more information click here
Similar samples:
Demo¶
Filtering depth using median filter
Setup¶
Please run the install script to download all required dependencies. Please note that this script must be ran from git context, so you have to download the depthai-python repository first and then run the script
git clone https://github.com/luxonis/depthai-python.git
cd depthai-python/examples
python3 install_requirements.py
For additional information, please follow installation guide
Source code¶
Also available on GitHub
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 | #!/usr/bin/env python3
import cv2
import depthai as dai
import numpy as np
# Closer-in minimum depth, disparity range is doubled (from 95 to 190):
extended_disparity = False
# Better accuracy for longer distance, fractional disparity 32-levels:
subpixel = False
# Better handling for occlusions:
lr_check = True
# Create pipeline
pipeline = dai.Pipeline()
# Define sources and outputs
monoLeft = pipeline.create(dai.node.MonoCamera)
monoRight = pipeline.create(dai.node.MonoCamera)
depth = pipeline.create(dai.node.StereoDepth)
xout = pipeline.create(dai.node.XLinkOut)
xout.setStreamName("disparity")
# Properties
monoLeft.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P)
monoLeft.setCamera("left")
monoRight.setResolution(dai.MonoCameraProperties.SensorResolution.THE_400_P)
monoRight.setCamera("right")
# Create a node that will produce the depth map (using disparity output as it's easier to visualize depth this way)
depth.setDefaultProfilePreset(dai.node.StereoDepth.PresetMode.HIGH_DENSITY)
# Options: MEDIAN_OFF, KERNEL_3x3, KERNEL_5x5, KERNEL_7x7 (default)
depth.initialConfig.setMedianFilter(dai.MedianFilter.KERNEL_7x7)
depth.setLeftRightCheck(lr_check)
depth.setExtendedDisparity(extended_disparity)
depth.setSubpixel(subpixel)
# Linking
monoLeft.out.link(depth.left)
monoRight.out.link(depth.right)
depth.disparity.link(xout.input)
# Connect to device and start pipeline
with dai.Device(pipeline) as device:
# Output queue will be used to get the disparity frames from the outputs defined above
q = device.getOutputQueue(name="disparity", maxSize=4, blocking=False)
while True:
inDisparity = q.get() # blocking call, will wait until a new data has arrived
frame = inDisparity.getFrame()
# Normalization for better visualization
frame = (frame * (255 / depth.initialConfig.getMaxDisparity())).astype(np.uint8)
cv2.imshow("disparity", frame)
# Available color maps: https://docs.opencv.org/3.4/d3/d50/group__imgproc__colormap.html
frame = cv2.applyColorMap(frame, cv2.COLORMAP_JET)
cv2.imshow("disparity_color", frame)
if cv2.waitKey(1) == ord('q'):
break
|
Also available on GitHub
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 | #include <iostream>
// Includes common necessary includes for development using depthai library
#include "depthai/depthai.hpp"
// Closer-in minimum depth, disparity range is doubled (from 95 to 190):
static std::atomic<bool> extended_disparity{false};
// Better accuracy for longer distance, fractional disparity 32-levels:
static std::atomic<bool> subpixel{false};
// Better handling for occlusions:
static std::atomic<bool> lr_check{true};
int main() {
// Create pipeline
dai::Pipeline pipeline;
// Define sources and outputs
auto monoLeft = pipeline.create<dai::node::MonoCamera>();
auto monoRight = pipeline.create<dai::node::MonoCamera>();
auto depth = pipeline.create<dai::node::StereoDepth>();
auto xout = pipeline.create<dai::node::XLinkOut>();
xout->setStreamName("disparity");
// Properties
monoLeft->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P);
monoLeft->setCamera("left");
monoRight->setResolution(dai::MonoCameraProperties::SensorResolution::THE_400_P);
monoRight->setCamera("right");
// Create a node that will produce the depth map (using disparity output as it's easier to visualize depth this way)
depth->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
// Options: MEDIAN_OFF, KERNEL_3x3, KERNEL_5x5, KERNEL_7x7 (default)
depth->initialConfig.setMedianFilter(dai::MedianFilter::KERNEL_7x7);
depth->setLeftRightCheck(lr_check);
depth->setExtendedDisparity(extended_disparity);
depth->setSubpixel(subpixel);
// Linking
monoLeft->out.link(depth->left);
monoRight->out.link(depth->right);
depth->disparity.link(xout->input);
// Connect to device and start pipeline
dai::Device device(pipeline);
// Output queue will be used to get the disparity frames from the outputs defined above
auto q = device.getOutputQueue("disparity", 4, false);
while(true) {
auto inDepth = q->get<dai::ImgFrame>();
auto frame = inDepth->getFrame();
// Normalization for better visualization
frame.convertTo(frame, CV_8UC1, 255 / depth->initialConfig.getMaxDisparity());
cv::imshow("disparity", frame);
// Available color maps: https://docs.opencv.org/3.4/d3/d50/group__imgproc__colormap.html
cv::applyColorMap(frame, frame, cv::COLORMAP_JET);
cv::imshow("disparity_color", frame);
int key = cv::waitKey(1);
if(key == 'q' || key == 'Q') {
return 0;
}
}
return 0;
}
|