rgb_depth_aligned.cpp
Go to the documentation of this file.
1 #include <cstdio>
2 #include <iostream>
3 
4 #include "utility.hpp"
5 
6 // Includes common necessary includes for development using depthai library
7 #include "depthai/depthai.hpp"
8 
9 // Optional. If set (true), the ColorCamera is downscaled from 1080p to 720p.
10 // Otherwise (false), the aligned depth is automatically upscaled to 1080p
11 static std::atomic<bool> downscaleColor{true};
12 static constexpr int fps = 30;
13 // The disparity is computed at this resolution, then upscaled to RGB resolution
15 
16 static float rgbWeight = 0.4f;
17 static float depthWeight = 0.6f;
18 
19 static void updateBlendWeights(int percentRgb, void* ctx) {
20  rgbWeight = float(percentRgb) / 100.f;
21  depthWeight = 1.f - rgbWeight;
22 }
23 
24 int main() {
25  using namespace std;
26 
27  // Create pipeline
28  dai::Pipeline pipeline;
29  dai::Device device;
30  std::vector<std::string> queueNames;
31 
32  // Define sources and outputs
33  auto camRgb = pipeline.create<dai::node::ColorCamera>();
34  auto left = pipeline.create<dai::node::MonoCamera>();
35  auto right = pipeline.create<dai::node::MonoCamera>();
36  auto stereo = pipeline.create<dai::node::StereoDepth>();
37 
38  auto rgbOut = pipeline.create<dai::node::XLinkOut>();
39  auto depthOut = pipeline.create<dai::node::XLinkOut>();
40 
41  rgbOut->setStreamName("rgb");
42  queueNames.push_back("rgb");
43  depthOut->setStreamName("depth");
44  queueNames.push_back("depth");
45 
46  // Properties
47  camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A);
49  camRgb->setFps(fps);
50  if(downscaleColor) camRgb->setIspScale(2, 3);
51  // For now, RGB needs fixed focus to properly align with depth.
52  // This value was used during calibration
53  try {
54  auto calibData = device.readCalibration2();
55  auto lensPosition = calibData.getLensPosition(dai::CameraBoardSocket::CAM_A);
56  if(lensPosition) {
57  camRgb->initialControl.setManualFocus(lensPosition);
58  }
59  } catch(const std::exception& ex) {
60  std::cout << ex.what() << std::endl;
61  return 1;
62  }
63 
64  left->setResolution(monoRes);
65  left->setCamera("left");
66  left->setFps(fps);
67  right->setResolution(monoRes);
68  right->setCamera("right");
69  right->setFps(fps);
70 
71  stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
72  // LR-check is required for depth alignment
73  stereo->setLeftRightCheck(true);
74  stereo->setDepthAlign(dai::CameraBoardSocket::CAM_A);
75 
76  // Linking
77  camRgb->isp.link(rgbOut->input);
78  left->out.link(stereo->left);
79  right->out.link(stereo->right);
80  stereo->disparity.link(depthOut->input);
81 
82  // Connect to device and start pipeline
83  device.startPipeline(pipeline);
84 
85  // Sets queues size and behavior
86  for(const auto& name : queueNames) {
87  device.getOutputQueue(name, 4, false);
88  }
89 
90  std::unordered_map<std::string, cv::Mat> frame;
91 
92  auto rgbWindowName = "rgb";
93  auto depthWindowName = "depth";
94  auto blendedWindowName = "rgb-depth";
95  cv::namedWindow(rgbWindowName);
96  cv::namedWindow(depthWindowName);
97  cv::namedWindow(blendedWindowName);
98  int defaultValue = (int)(rgbWeight * 100);
99  cv::createTrackbar("RGB Weight %", blendedWindowName, &defaultValue, 100, updateBlendWeights);
100 
101  while(true) {
102  std::unordered_map<std::string, std::shared_ptr<dai::ImgFrame>> latestPacket;
103 
104  auto queueEvents = device.getQueueEvents(queueNames);
105  for(const auto& name : queueEvents) {
106  auto packets = device.getOutputQueue(name)->tryGetAll<dai::ImgFrame>();
107  auto count = packets.size();
108  if(count > 0) {
109  latestPacket[name] = packets[count - 1];
110  }
111  }
112 
113  for(const auto& name : queueNames) {
114  if(latestPacket.find(name) != latestPacket.end()) {
115  if(name == depthWindowName) {
116  frame[name] = latestPacket[name]->getFrame();
117  auto maxDisparity = stereo->initialConfig.getMaxDisparity();
118  // Optional, extend range 0..95 -> 0..255, for a better visualisation
119  if(1) frame[name].convertTo(frame[name], CV_8UC1, 255. / maxDisparity);
120  // Optional, apply false colorization
121  if(1) cv::applyColorMap(frame[name], frame[name], cv::COLORMAP_HOT);
122  } else {
123  frame[name] = latestPacket[name]->getCvFrame();
124  }
125 
126  cv::imshow(name, frame[name]);
127  }
128  }
129 
130  // Blend when both received
131  if(frame.find(rgbWindowName) != frame.end() && frame.find(depthWindowName) != frame.end()) {
132  // Need to have both frames in BGR format before blending
133  if(frame[depthWindowName].channels() < 3) {
134  cv::cvtColor(frame[depthWindowName], frame[depthWindowName], cv::COLOR_GRAY2BGR);
135  }
136  cv::Mat blended;
137  cv::addWeighted(frame[rgbWindowName], rgbWeight, frame[depthWindowName], depthWeight, 0, blended);
138  cv::imshow(blendedWindowName, blended);
139  frame.clear();
140  }
141 
142  int key = cv::waitKey(1);
143  if(key == 'q' || key == 'Q') {
144  return 0;
145  }
146  }
147  return 0;
148 }
dai::node::MonoCamera::out
Output out
Definition: MonoCamera.hpp:47
dai::DeviceBase::startPipeline
bool startPipeline()
Definition: DeviceBase.cpp:1511
dai::node::XLinkOut
XLinkOut node. Sends messages over XLink.
Definition: XLinkOut.hpp:14
dai::node::MonoCamera::setCamera
void setCamera(std::string name)
Definition: MonoCamera.cpp:36
dai::Pipeline
Represents the pipeline, set of nodes and connections between them.
Definition: Pipeline.hpp:100
dai::node::MonoCamera::setFps
void setFps(float fps)
Definition: MonoCamera.cpp:98
dai::ImgFrame::getFrame
void getFrame(T...)
Definition: ImgFrame.hpp:218
dai::node::ColorCamera::setResolution
void setResolution(Properties::SensorResolution resolution)
Set sensor resolution.
Definition: ColorCamera.cpp:169
dai::node::StereoDepth
StereoDepth node. Compute stereo disparity and depth from left-right image pair.
Definition: StereoDepth.hpp:15
rgbWeight
static float rgbWeight
Definition: rgb_depth_aligned.cpp:16
dai::node::ColorCamera::setFps
void setFps(float fps)
Definition: ColorCamera.cpp:176
fps
static constexpr int fps
Definition: rgb_depth_aligned.cpp:12
dai::CameraBoardSocket::CAM_A
@ CAM_A
dai::node::MonoCamera
MonoCamera node. For use with grayscale sensors.
Definition: MonoCamera.hpp:17
dai::node::ColorCamera
ColorCamera node. For use with color sensors.
Definition: ColorCamera.hpp:16
dai::Device::getOutputQueue
std::shared_ptr< DataOutputQueue > getOutputQueue(const std::string &name)
Definition: Device.cpp:86
dai::MonoCameraProperties::SensorResolution::THE_720_P
@ THE_720_P
dai::node::XLinkOut::input
Input input
Definition: XLinkOut.hpp:27
depthai.hpp
dai::Pipeline::create
std::shared_ptr< N > create()
Definition: Pipeline.hpp:145
dai::node::MonoCamera::setResolution
void setResolution(Properties::SensorResolution resolution)
Set sensor resolution.
Definition: MonoCamera.cpp:82
depthWeight
static float depthWeight
Definition: rgb_depth_aligned.cpp:17
dai::ImgFrame
Definition: ImgFrame.hpp:25
dai::ColorCameraProperties::SensorResolution::THE_1080_P
@ THE_1080_P
1920 × 1080
dai::DeviceBase::readCalibration2
CalibrationHandler readCalibration2()
Definition: DeviceBase.cpp:1385
dai::node::StereoDepth::PresetMode::HIGH_DENSITY
@ HIGH_DENSITY
dai::Device
Definition: Device.hpp:21
main
int main()
Definition: rgb_depth_aligned.cpp:24
dai::CalibrationHandler::getLensPosition
uint8_t getLensPosition(CameraBoardSocket cameraId) const
Definition: CalibrationHandler.cpp:343
std
Definition: Node.hpp:366
downscaleColor
static std::atomic< bool > downscaleColor
Definition: rgb_depth_aligned.cpp:11
dai::Device::getQueueEvents
std::vector< std::string > getQueueEvents(const std::vector< std::string > &queueNames, std::size_t maxNumEvents=std::numeric_limits< std::size_t >::max(), std::chrono::microseconds timeout=std::chrono::microseconds(-1))
Definition: Device.cpp:164
dai::Node::Output::link
void link(const Input &in)
Definition: Node.cpp:84
dai::node::XLinkOut::setStreamName
void setStreamName(const std::string &name)
Definition: XLinkOut.cpp:13
monoRes
static constexpr auto monoRes
Definition: rgb_depth_aligned.cpp:14
utility.hpp
dai::node::ColorCamera::setCamera
void setCamera(std::string name)
Definition: ColorCamera.cpp:44
updateBlendWeights
static void updateBlendWeights(int percentRgb, void *ctx)
Definition: rgb_depth_aligned.cpp:19


depthai
Author(s): Martin Peterlin
autogenerated on Sat Mar 22 2025 02:58:19